mirror of
https://github.com/moveit/moveit_task_constructor.git
synced 2025-11-04 14:49:57 +08:00
reduce copying of shared ptrs
This commit is contained in:
parent
d648a4091e
commit
36fe4c98be
@ -59,14 +59,14 @@ public:
|
||||
|
||||
void init(const moveit::core::RobotModelConstPtr& robot_model) override;
|
||||
|
||||
bool plan(const planning_scene::PlanningSceneConstPtr from,
|
||||
const planning_scene::PlanningSceneConstPtr to,
|
||||
bool 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;
|
||||
|
||||
bool plan(const planning_scene::PlanningSceneConstPtr from,
|
||||
bool plan(const planning_scene::PlanningSceneConstPtr& from,
|
||||
const moveit::core::LinkModel &link,
|
||||
const Eigen::Affine3d& target,
|
||||
const moveit::core::JointModelGroup *jmg,
|
||||
|
||||
@ -55,14 +55,14 @@ public:
|
||||
|
||||
void init(const moveit::core::RobotModelConstPtr& robot_model) override;
|
||||
|
||||
bool plan(const planning_scene::PlanningSceneConstPtr from,
|
||||
const planning_scene::PlanningSceneConstPtr to,
|
||||
bool plan(const planning_scene::PlanningSceneConstPtr& from,
|
||||
const planning_scene::PlanningSceneConstPtr& to,
|
||||
const core::JointModelGroup *jmg,
|
||||
double timeout,
|
||||
robot_trajectory::RobotTrajectoryPtr& result,
|
||||
const moveit_msgs::Constraints& path_constraints= moveit_msgs::Constraints()) override;
|
||||
|
||||
bool plan(const planning_scene::PlanningSceneConstPtr from,
|
||||
bool plan(const planning_scene::PlanningSceneConstPtr& from,
|
||||
const moveit::core::LinkModel &link,
|
||||
const Eigen::Affine3d& target,
|
||||
const core::JointModelGroup *jmg,
|
||||
|
||||
@ -58,14 +58,14 @@ public:
|
||||
|
||||
void init(const moveit::core::RobotModelConstPtr& robot_model) override;
|
||||
|
||||
bool plan(const planning_scene::PlanningSceneConstPtr from,
|
||||
const planning_scene::PlanningSceneConstPtr to,
|
||||
bool plan(const planning_scene::PlanningSceneConstPtr& from,
|
||||
const planning_scene::PlanningSceneConstPtr& to,
|
||||
const core::JointModelGroup *jmg,
|
||||
double timeout,
|
||||
robot_trajectory::RobotTrajectoryPtr& result,
|
||||
const moveit_msgs::Constraints& path_constraints= moveit_msgs::Constraints()) override;
|
||||
|
||||
bool plan(const planning_scene::PlanningSceneConstPtr from,
|
||||
bool plan(const planning_scene::PlanningSceneConstPtr& from,
|
||||
const moveit::core::LinkModel &link,
|
||||
const Eigen::Affine3d& target,
|
||||
const core::JointModelGroup *jmg,
|
||||
|
||||
@ -75,15 +75,15 @@ public:
|
||||
virtual void init(const moveit::core::RobotModelConstPtr& robot_model) = 0;
|
||||
|
||||
/// plan trajectory between to robot states
|
||||
virtual bool plan(const planning_scene::PlanningSceneConstPtr from,
|
||||
const planning_scene::PlanningSceneConstPtr to,
|
||||
virtual bool 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()) = 0;
|
||||
|
||||
/// plan trajectory from current robot state to Cartesian target
|
||||
virtual bool plan(const planning_scene::PlanningSceneConstPtr from,
|
||||
virtual bool plan(const planning_scene::PlanningSceneConstPtr& from,
|
||||
const moveit::core::LinkModel &link,
|
||||
const Eigen::Affine3d& target,
|
||||
const moveit::core::JointModelGroup *jmg,
|
||||
|
||||
@ -80,7 +80,8 @@ public:
|
||||
~Task();
|
||||
|
||||
std::string id() const;
|
||||
const moveit::core::RobotModelConstPtr getRobotModel() const { return robot_model_; }
|
||||
|
||||
const moveit::core::RobotModelConstPtr& getRobotModel() const { return robot_model_; }
|
||||
/// setting the robot model also resets the task
|
||||
void setRobotModel(const moveit::core::RobotModelConstPtr& robot_model);
|
||||
/// load robot model from given parameter
|
||||
|
||||
@ -56,8 +56,8 @@ void CartesianPath::init(const core::RobotModelConstPtr &robot_model)
|
||||
{
|
||||
}
|
||||
|
||||
bool CartesianPath::plan(const planning_scene::PlanningSceneConstPtr from,
|
||||
const planning_scene::PlanningSceneConstPtr to,
|
||||
bool CartesianPath::plan(const planning_scene::PlanningSceneConstPtr& from,
|
||||
const planning_scene::PlanningSceneConstPtr& to,
|
||||
const moveit::core::JointModelGroup *jmg,
|
||||
double timeout,
|
||||
robot_trajectory::RobotTrajectoryPtr& result,
|
||||
@ -74,7 +74,7 @@ bool CartesianPath::plan(const planning_scene::PlanningSceneConstPtr from,
|
||||
jmg, timeout, result, path_constraints);
|
||||
}
|
||||
|
||||
bool CartesianPath::plan(const planning_scene::PlanningSceneConstPtr from,
|
||||
bool CartesianPath::plan(const planning_scene::PlanningSceneConstPtr& from,
|
||||
const moveit::core::LinkModel &link,
|
||||
const Eigen::Affine3d &target,
|
||||
const moveit::core::JointModelGroup *jmg,
|
||||
|
||||
@ -54,8 +54,8 @@ void JointInterpolationPlanner::init(const core::RobotModelConstPtr &robot_model
|
||||
{
|
||||
}
|
||||
|
||||
bool JointInterpolationPlanner::plan(const planning_scene::PlanningSceneConstPtr from,
|
||||
const planning_scene::PlanningSceneConstPtr to,
|
||||
bool JointInterpolationPlanner::plan(const planning_scene::PlanningSceneConstPtr& from,
|
||||
const planning_scene::PlanningSceneConstPtr& to,
|
||||
const moveit::core::JointModelGroup *jmg,
|
||||
double timeout,
|
||||
robot_trajectory::RobotTrajectoryPtr& result,
|
||||
@ -99,7 +99,7 @@ bool JointInterpolationPlanner::plan(const planning_scene::PlanningSceneConstPtr
|
||||
return true;
|
||||
}
|
||||
|
||||
bool JointInterpolationPlanner::plan(const planning_scene::PlanningSceneConstPtr from,
|
||||
bool JointInterpolationPlanner::plan(const planning_scene::PlanningSceneConstPtr& from,
|
||||
const moveit::core::LinkModel &link,
|
||||
const Eigen::Affine3d& target_eigen,
|
||||
const moveit::core::JointModelGroup *jmg,
|
||||
|
||||
@ -82,8 +82,8 @@ void initMotionPlanRequest(moveit_msgs::MotionPlanRequest& req,
|
||||
req.workspace_parameters = p.get<moveit_msgs::WorkspaceParameters>("workspace_parameters");
|
||||
}
|
||||
|
||||
bool PipelinePlanner::plan(const planning_scene::PlanningSceneConstPtr from,
|
||||
const planning_scene::PlanningSceneConstPtr to,
|
||||
bool PipelinePlanner::plan(const planning_scene::PlanningSceneConstPtr& from,
|
||||
const planning_scene::PlanningSceneConstPtr& to,
|
||||
const moveit::core::JointModelGroup *jmg,
|
||||
double timeout,
|
||||
robot_trajectory::RobotTrajectoryPtr& result,
|
||||
@ -107,7 +107,7 @@ bool PipelinePlanner::plan(const planning_scene::PlanningSceneConstPtr from,
|
||||
return true;
|
||||
}
|
||||
|
||||
bool PipelinePlanner::plan(const planning_scene::PlanningSceneConstPtr from,
|
||||
bool PipelinePlanner::plan(const planning_scene::PlanningSceneConstPtr& from,
|
||||
const moveit::core::LinkModel &link,
|
||||
const Eigen::Affine3d& target_eigen,
|
||||
const moveit::core::JointModelGroup *jmg,
|
||||
|
||||
Loading…
Reference in New Issue
Block a user