Namespaces | Functions
generate_motion_plan.h File Reference
#include <descartes_core/robot_model.h>
#include <choreo_descartes_planner/constrained_segment.h>
#include <choreo_msgs/UnitProcessPlan.h>
#include <choreo_msgs/ElementCandidatePoses.h>
#include <choreo_msgs/WireFrameCollisionObject.h>
#include <choreo_msgs/AssemblySequencePickNPlace.h>
#include <moveit_msgs/CollisionObject.h>
Include dependency graph for generate_motion_plan.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Namespaces

 choreo_process_planning
 

Functions

void choreo_process_planning::adjustTrajectoryTiming (std::vector< choreo_msgs::UnitProcessPlan > &plans, const std::vector< std::string > &joint_names, const std::string world_frame)
 
void choreo_process_planning::appendTCPPoseToPlans (const descartes_core::RobotModelPtr model, const std::vector< planning_scene::PlanningScenePtr > &planning_scenes_shrinked, const std::vector< planning_scene::PlanningScenePtr > &planning_scenes_full, std::vector< choreo_msgs::UnitProcessPlan > &plans)
 
bool choreo_process_planning::generateMotionPlan (const std::string world_frame, const bool use_saved_graph, const std::string &saved_graph_file_name, const double clt_rrt_unit_process_timeout, const double clt_rrt_timeout, const std::string &move_group_name, const std::vector< double > &start_state, const std::vector< choreo_msgs::ElementCandidatePoses > &task_seq, const std::vector< choreo_msgs::WireFrameCollisionObject > &wf_collision_objs, std::vector< descartes_planner::ConstrainedSegment > &segs, descartes_core::RobotModelPtr model, moveit::core::RobotModelConstPtr moveit_model, ros::ServiceClient &planning_scene_diff_client, std::vector< choreo_msgs::UnitProcessPlan > &plans)
 
bool choreo_process_planning::generateMotionPlan (const std::string world_frame, const bool use_saved_graph, const std::string &saved_graph_file_name, const double clt_rrt_unit_process_timeout, const double clt_rrt_timeout, const double &linear_vel, const double &linear_disc, const std::string &move_group_name, const std::vector< double > &start_state, const choreo_msgs::AssemblySequencePickNPlace &as_pnp, descartes_core::RobotModelPtr model, moveit::core::RobotModelConstPtr moveit_model, ros::ServiceClient &planning_scene_diff_client, std::vector< choreo_msgs::UnitProcessPlan > &plans)
 
void choreo_process_planning::retractionPlanning (descartes_core::RobotModelPtr model, const std::vector< planning_scene::PlanningScenePtr > &planning_scenes_approach, const std::vector< planning_scene::PlanningScenePtr > &planning_scenes_depart, const std::vector< descartes_planner::ConstrainedSegment > &segs, std::vector< choreo_msgs::UnitProcessPlan > &plans)
 
void choreo_process_planning::transitionPlanning (std::vector< choreo_msgs::UnitProcessPlan > &plans, moveit::core::RobotModelConstPtr moveit_model, ros::ServiceClient &planning_scene_diff_client, const std::string &move_group_name, const std::vector< double > &start_state, std::vector< planning_scene::PlanningScenePtr > &planning_scenes)
 


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