From 55c4b52b13ab8fe86bd275815bfa21eef8e0c19c Mon Sep 17 00:00:00 2001 From: Robert Haschke Date: Sat, 9 Mar 2024 09:20:43 +0100 Subject: [PATCH] Cosmetic fixes --- .../moveit/task_constructor/solvers/cartesian_path.h | 10 +++++----- core/src/stages/generate_random_pose.cpp | 4 ++-- core/test/CMakeLists.txt | 2 +- core/test/stage_mockups.cpp | 2 -- 4 files changed, 8 insertions(+), 10 deletions(-) diff --git a/core/include/moveit/task_constructor/solvers/cartesian_path.h b/core/include/moveit/task_constructor/solvers/cartesian_path.h index 3a6c06041..1a4552d7c 100644 --- a/core/include/moveit/task_constructor/solvers/cartesian_path.h +++ b/core/include/moveit/task_constructor/solvers/cartesian_path.h @@ -64,13 +64,13 @@ class CartesianPath : public PlannerInterface void init(const moveit::core::RobotModelConstPtr& robot_model) override; Result plan(const planning_scene::PlanningSceneConstPtr& from, const planning_scene::PlanningSceneConstPtr& to, - const moveit::core::JointModelGroup* jmg, double timeout, robot_trajectory::RobotTrajectoryPtr& result, - const moveit_msgs::Constraints& path_constraints = moveit_msgs::Constraints()) override; + const moveit::core::JointModelGroup* jmg, double timeout, robot_trajectory::RobotTrajectoryPtr& result, + const moveit_msgs::Constraints& path_constraints = moveit_msgs::Constraints()) override; Result plan(const planning_scene::PlanningSceneConstPtr& from, const moveit::core::LinkModel& link, - const Eigen::Isometry3d& offset, const Eigen::Isometry3d& target, const moveit::core::JointModelGroup* jmg, - double timeout, robot_trajectory::RobotTrajectoryPtr& result, - const moveit_msgs::Constraints& path_constraints = moveit_msgs::Constraints()) override; + const Eigen::Isometry3d& offset, const Eigen::Isometry3d& target, const moveit::core::JointModelGroup* jmg, + double timeout, robot_trajectory::RobotTrajectoryPtr& result, + const moveit_msgs::Constraints& path_constraints = moveit_msgs::Constraints()) override; }; } // namespace solvers } // namespace task_constructor diff --git a/core/src/stages/generate_random_pose.cpp b/core/src/stages/generate_random_pose.cpp index fcb310d88..51cf9c533 100644 --- a/core/src/stages/generate_random_pose.cpp +++ b/core/src/stages/generate_random_pose.cpp @@ -90,7 +90,7 @@ void GenerateRandomPose::compute() { const SolutionBase& s = *upstream_solutions_.pop(); planning_scene::PlanningScenePtr scene = s.end()->scene()->diff(); - geometry_msgs::PoseStamped seed_pose = properties().get("pose"); + auto seed_pose = properties().get("pose"); if (seed_pose.header.frame_id.empty()) seed_pose.header.frame_id = scene->getPlanningFrame(); else if (!scene->knowsFrameTransform(seed_pose.header.frame_id)) { @@ -116,7 +116,7 @@ void GenerateRandomPose::compute() { if (pose_dimension_samplers_.empty()) return; - geometry_msgs::PoseStamped sample_pose = seed_pose; + auto sample_pose = seed_pose; Eigen::Isometry3d seed, sample; tf2::fromMsg(seed_pose.pose, seed); double elapsed_time = 0.0; diff --git a/core/test/CMakeLists.txt b/core/test/CMakeLists.txt index b9709651f..09e6d477b 100644 --- a/core/test/CMakeLists.txt +++ b/core/test/CMakeLists.txt @@ -38,7 +38,7 @@ if (CATKIN_ENABLE_TESTING) mtc_add_gtest(test_stage.cpp) mtc_add_gtest(test_container.cpp) mtc_add_gmock(test_serial.cpp) - mtc_add_gtest(test_pruning.cpp) + mtc_add_gmock(test_pruning.cpp) mtc_add_gtest(test_properties.cpp) mtc_add_gtest(test_cost_terms.cpp) diff --git a/core/test/stage_mockups.cpp b/core/test/stage_mockups.cpp index 9397be569..37be534c3 100644 --- a/core/test/stage_mockups.cpp +++ b/core/test/stage_mockups.cpp @@ -3,8 +3,6 @@ #include "stage_mockups.h" -#include - namespace moveit { namespace task_constructor {