semi_constrained_cartesian_planning.h
Go to the documentation of this file.
1 //
2 // Created by yijiangh on 4/10/18.
3 //
4 
5 #ifndef CHOREO_MPP_SEMI_CONSTRAINED_CARTESIAN_PLANNING_H
6 #define CHOREO_MPP_SEMI_CONSTRAINED_CARTESIAN_PLANNING_H
7 
9 
10 #include <descartes_core/robot_model.h>
11 
12 #include <choreo_msgs/UnitProcessPlan.h>
13 #include <choreo_msgs/ElementCandidatePoses.h>
14 #include <choreo_msgs/AssemblySequencePickNPlace.h>
15 
17 {
18 // overhead for spatial extrusion
19 void CLTRRTforProcessROSTraj(descartes_core::RobotModelPtr model,
20  std::vector <descartes_planner::ConstrainedSegment> &segs,
21  const double clt_rrt_unit_process_timeout,
22  const double clt_rrt_timeout,
23  const std::vector <planning_scene::PlanningScenePtr> &planning_scenes_approach,
24  const std::vector <planning_scene::PlanningScenePtr> &planning_scenes_depart,
25  const std::vector <choreo_msgs::ElementCandidatePoses> &task_seq,
26  std::vector <choreo_msgs::UnitProcessPlan> &plans,
27  const std::string &saved_graph_file_name,
28  bool use_saved_graph);
29 
30 // TODO: overhead for picknplace
31 void CLTRRTforProcessROSTraj(descartes_core::RobotModelPtr model,
32  const choreo_msgs::AssemblySequencePickNPlace& as_pnp,
33  const double clt_rrt_unit_process_timeout,
34  const double clt_rrt_timeout,
35  const double& linear_vel,
36  const double& linear_disc,
37  const std::vector<std::vector<planning_scene::PlanningScenePtr>>& planning_scenes_subprocess,
38  std::vector <choreo_msgs::UnitProcessPlan>& plans,
39  const std::string &saved_graph_file_name,
40  bool use_saved_grap);
41 }
42 
43 #endif //CHOREO_MPP_SEMI_CONSTRAINED_CARTESIAN_PLANNING_H
void CLTRRTforProcessROSTraj(descartes_core::RobotModelPtr model, std::vector< descartes_planner::ConstrainedSegment > &segs, const double clt_rrt_unit_process_timeout, const double clt_rrt_timeout, const std::vector< planning_scene::PlanningScenePtr > &planning_scenes_approach, const std::vector< planning_scene::PlanningScenePtr > &planning_scenes_depart, const std::vector< choreo_msgs::ElementCandidatePoses > &task_seq, std::vector< choreo_msgs::UnitProcessPlan > &plans, const std::string &saved_graph_file_name, bool use_saved_graph)


choreo_process_planning
Author(s): Yijiang Huang
autogenerated on Thu Jul 18 2019 03:59:02