Cosmetic fixes

This commit is contained in:
Robert Haschke 2024-03-09 09:20:43 +01:00
parent 795bde7b62
commit 55c4b52b13
4 changed files with 8 additions and 10 deletions

View File

@ -64,13 +64,13 @@ public:
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

View File

@ -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<geometry_msgs::PoseStamped>("pose");
auto seed_pose = properties().get<geometry_msgs::PoseStamped>("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;

View File

@ -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)

View File

@ -3,8 +3,6 @@
#include "stage_mockups.h"
#include <gtest/gtest.h>
namespace moveit {
namespace task_constructor {