Skip to content

Commit 55c4b52

Browse files
committed
Cosmetic fixes
1 parent 795bde7 commit 55c4b52

File tree

4 files changed

+8
-10
lines changed

4 files changed

+8
-10
lines changed

core/include/moveit/task_constructor/solvers/cartesian_path.h

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -64,13 +64,13 @@ class CartesianPath : public PlannerInterface
6464
void init(const moveit::core::RobotModelConstPtr& robot_model) override;
6565

6666
Result plan(const planning_scene::PlanningSceneConstPtr& from, const planning_scene::PlanningSceneConstPtr& to,
67-
const moveit::core::JointModelGroup* jmg, double timeout, robot_trajectory::RobotTrajectoryPtr& result,
68-
const moveit_msgs::Constraints& path_constraints = moveit_msgs::Constraints()) override;
67+
const moveit::core::JointModelGroup* jmg, double timeout, robot_trajectory::RobotTrajectoryPtr& result,
68+
const moveit_msgs::Constraints& path_constraints = moveit_msgs::Constraints()) override;
6969

7070
Result plan(const planning_scene::PlanningSceneConstPtr& from, const moveit::core::LinkModel& link,
71-
const Eigen::Isometry3d& offset, const Eigen::Isometry3d& target, const moveit::core::JointModelGroup* jmg,
72-
double timeout, robot_trajectory::RobotTrajectoryPtr& result,
73-
const moveit_msgs::Constraints& path_constraints = moveit_msgs::Constraints()) override;
71+
const Eigen::Isometry3d& offset, const Eigen::Isometry3d& target, const moveit::core::JointModelGroup* jmg,
72+
double timeout, robot_trajectory::RobotTrajectoryPtr& result,
73+
const moveit_msgs::Constraints& path_constraints = moveit_msgs::Constraints()) override;
7474
};
7575
} // namespace solvers
7676
} // namespace task_constructor

core/src/stages/generate_random_pose.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -90,7 +90,7 @@ void GenerateRandomPose::compute() {
9090

9191
const SolutionBase& s = *upstream_solutions_.pop();
9292
planning_scene::PlanningScenePtr scene = s.end()->scene()->diff();
93-
geometry_msgs::PoseStamped seed_pose = properties().get<geometry_msgs::PoseStamped>("pose");
93+
auto seed_pose = properties().get<geometry_msgs::PoseStamped>("pose");
9494
if (seed_pose.header.frame_id.empty())
9595
seed_pose.header.frame_id = scene->getPlanningFrame();
9696
else if (!scene->knowsFrameTransform(seed_pose.header.frame_id)) {
@@ -116,7 +116,7 @@ void GenerateRandomPose::compute() {
116116
if (pose_dimension_samplers_.empty())
117117
return;
118118

119-
geometry_msgs::PoseStamped sample_pose = seed_pose;
119+
auto sample_pose = seed_pose;
120120
Eigen::Isometry3d seed, sample;
121121
tf2::fromMsg(seed_pose.pose, seed);
122122
double elapsed_time = 0.0;

core/test/CMakeLists.txt

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -38,7 +38,7 @@ if (CATKIN_ENABLE_TESTING)
3838
mtc_add_gtest(test_stage.cpp)
3939
mtc_add_gtest(test_container.cpp)
4040
mtc_add_gmock(test_serial.cpp)
41-
mtc_add_gtest(test_pruning.cpp)
41+
mtc_add_gmock(test_pruning.cpp)
4242
mtc_add_gtest(test_properties.cpp)
4343
mtc_add_gtest(test_cost_terms.cpp)
4444

core/test/stage_mockups.cpp

Lines changed: 0 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -3,8 +3,6 @@
33

44
#include "stage_mockups.h"
55

6-
#include <gtest/gtest.h>
7-
86
namespace moveit {
97
namespace task_constructor {
108

0 commit comments

Comments
 (0)