Public Member Functions | Private Member Functions | Private Attributes | List of all members
ChoreoCoreService Class Reference

#include <choreo_core_service.h>

Public Member Functions

 ChoreoCoreService ()
 
bool init ()
 
void run ()
 

Private Member Functions

void adjustSimSpeed (double sim_speed)
 
int checkSavedLadderGraphSize (const std::string &filename)
 
bool choreoParametersServerCallback (choreo_msgs::ChoreoParameters::Request &req, choreo_msgs::ChoreoParameters::Response &res)
 
bool elementNumberRequestServerCallback (choreo_msgs::ElementNumberRequest::Request &req, choreo_msgs::ElementNumberRequest::Response &res)
 
bool generateMotionLibrary (const int selected_path_index, choreo_core_service::TrajectoryLibrary &traj_lib)
 
bool generatePicknPlaceMotionLibrary ()
 
ProcessPlanResult generateProcessPlan (const int &index)
 
bool getAvailableProcessPlansCallback (choreo_msgs::GetAvailableProcessPlans::Request &req, choreo_msgs::GetAvailableProcessPlans::Response &res)
 
bool loadModelInputParameters (const std::string &filename)
 
bool loadOutputSaveDirInputParameters (const std::string &filename)
 
bool loadRobotInputParameters (const std::string &filename)
 
bool loadTaskSequenceInputParameters (const std::string &filename)
 
bool moveToTargetJointPose (std::vector< double > joint_pose)
 
bool outputProcessPlansCallback (choreo_msgs::OutputProcessPlans::Request &req, choreo_msgs::OutputProcessPlans::Response &res)
 
void processPlanningActionCallback (const choreo_msgs::ProcessPlanningGoalConstPtr &goal)
 
bool queryComputationResultCallback (choreo_msgs::QueryComputationRecord::Request &req, choreo_msgs::QueryComputationRecord::Response &res)
 
void saveModelInputParameters (const std::string &filename)
 
void saveOutputSaveDirInputParameters (const std::string &filename)
 
void saveRobotInputParameters (const std::string &filename)
 
void saveTaskSequenceInputParameters (const std::string &filename)
 
void simulateMotionPlansActionCallback (const choreo_msgs::SimulateMotionPlanGoalConstPtr &goal_in)
 
void taskSequencePlanningActionCallback (const choreo_msgs::TaskSequencePlanningGoalConstPtr &goal)
 
void taskSequenceProcessingActionCallback (const choreo_msgs::TaskSequenceProcessingGoalConstPtr &goal)
 
bool visualizeSelectedPathServerCallback (choreo_msgs::VisualizeSelectedPath::Request &req, choreo_msgs::VisualizeSelectedPath::Response &res)
 

Private Attributes

choreo_msgs::AssemblySequencePickNPlace as_pnp_
 
std::string assembly_type_
 
actionlib::SimpleActionClient< choreo_msgs::ProcessExecutionAction > choreo_exe_client_
 
ros::ServiceServer choreo_parameters_server_
 
choreo_msgs::ModelInputParameters default_model_input_params_
 
choreo_msgs::OutputSaveDirInputParameters default_output_save_dir_input_params_
 
choreo_msgs::RobotInputParameters default_robot_input_params_
 
choreo_msgs::TaskSequenceInputParameters default_task_sequence_input_params_
 
ros::ServiceServer element_number_sequest_server_
 
std::vector< moveit_msgs::CollisionObject > env_objs_
 
ros::ServiceServer get_available_process_plans_server_
 
choreo_msgs::ModelInputParameters model_input_params_
 
ros::ServiceClient move_to_pose_client_
 
ros::NodeHandle nh_
 
ros::ServiceServer output_process_plans_server_
 
ros::ServiceClient output_processing_client_
 
choreo_msgs::OutputSaveDirInputParameters output_save_dir_input_params_
 
std::string param_cache_prefix_
 
ros::ServiceClient process_planning_client_
 
choreo_msgs::ProcessPlanningFeedback process_planning_feedback_
 
choreo_msgs::ProcessPlanningResult process_planning_result_
 
actionlib::SimpleActionServer< choreo_msgs::ProcessPlanningAction > process_planning_server_
 
ros::ServiceServer query_computation_result_server_
 
choreo_msgs::RobotInputParameters robot_input_params_
 
bool save_data_
 
std::string save_location_
 
int selected_task_id_
 
choreo_msgs::SimulateMotionPlanFeedback simulate_motion_plan_feedback_
 
choreo_msgs::SimulateMotionPlanResult simulate_motion_plan_result_
 
actionlib::SimpleActionServer< choreo_msgs::SimulateMotionPlanAction > simulate_motion_plan_server_
 
std::vector< choreo_msgs::ElementCandidatePoses > task_sequence_
 
choreo_msgs::TaskSequenceInputParameters task_sequence_input_params_
 
choreo_msgs::TaskSequencePlanningFeedback task_sequence_planning_feedback_
 
choreo_msgs::TaskSequencePlanningResult task_sequence_planning_result_
 
actionlib::SimpleActionServer< choreo_msgs::TaskSequencePlanningAction > task_sequence_planning_server_
 
ros::ServiceClient task_sequence_planning_srv_client_
 
choreo_msgs::TaskSequenceProcessingFeedback task_sequence_processing_feedback_
 
choreo_msgs::TaskSequenceProcessingResult task_sequence_processing_result_
 
actionlib::SimpleActionServer< choreo_msgs::TaskSequenceProcessingAction > task_sequence_processing_server_
 
ros::ServiceClient task_sequence_processing_srv_client_
 
choreo_core_service::TrajectoryLibrary trajectory_library_
 
bool use_saved_graph_
 
choreo_visual_tools::ChoreoVisualTools visual_tools_
 
ros::ServiceServer visualize_selected_path_server_
 
std::string world_frame_
 

Detailed Description

Definition at line 47 of file choreo_core_service.h.

Constructor & Destructor Documentation

ChoreoCoreService::ChoreoCoreService ( )

Definition at line 65 of file choreo_core_service.cpp.

Member Function Documentation

void ChoreoCoreService::adjustSimSpeed ( double  sim_speed)
private
int ChoreoCoreService::checkSavedLadderGraphSize ( const std::string &  filename)
private

Definition at line 267 of file choreo_core_service.cpp.

bool ChoreoCoreService::choreoParametersServerCallback ( choreo_msgs::ChoreoParameters::Request &  req,
choreo_msgs::ChoreoParameters::Response &  res 
)
private

Definition at line 283 of file choreo_core_service.cpp.

bool ChoreoCoreService::elementNumberRequestServerCallback ( choreo_msgs::ElementNumberRequest::Request &  req,
choreo_msgs::ElementNumberRequest::Response &  res 
)
private

Definition at line 326 of file choreo_core_service.cpp.

bool ChoreoCoreService::generateMotionLibrary ( const int  selected_path_index,
choreo_core_service::TrajectoryLibrary traj_lib 
)
private

Definition at line 13 of file choreo_core_service_process_planning.cpp.

bool ChoreoCoreService::generatePicknPlaceMotionLibrary ( )
private
ProcessPlanResult ChoreoCoreService::generateProcessPlan ( const int &  index)
private

Definition at line 27 of file choreo_core_service_process_planning.cpp.

bool ChoreoCoreService::getAvailableProcessPlansCallback ( choreo_msgs::GetAvailableProcessPlans::Request &  req,
choreo_msgs::GetAvailableProcessPlans::Response &  res 
)
private

Definition at line 403 of file choreo_core_service.cpp.

bool ChoreoCoreService::init ( )

Definition at line 80 of file choreo_core_service.cpp.

bool ChoreoCoreService::loadModelInputParameters ( const std::string &  filename)
private

Definition at line 165 of file choreo_core_service.cpp.

bool ChoreoCoreService::loadOutputSaveDirInputParameters ( const std::string &  filename)
private

Definition at line 244 of file choreo_core_service.cpp.

bool ChoreoCoreService::loadRobotInputParameters ( const std::string &  filename)
private

Definition at line 221 of file choreo_core_service.cpp.

bool ChoreoCoreService::loadTaskSequenceInputParameters ( const std::string &  filename)
private

Definition at line 198 of file choreo_core_service.cpp.

bool ChoreoCoreService::moveToTargetJointPose ( std::vector< double >  joint_pose)
private

Definition at line 117 of file choreo_core_service_process_planning.cpp.

bool ChoreoCoreService::outputProcessPlansCallback ( choreo_msgs::OutputProcessPlans::Request &  req,
choreo_msgs::OutputProcessPlans::Response &  res 
)
private

Definition at line 415 of file choreo_core_service.cpp.

void ChoreoCoreService::processPlanningActionCallback ( const choreo_msgs::ProcessPlanningGoalConstPtr &  goal)
private

Definition at line 598 of file choreo_core_service.cpp.

bool ChoreoCoreService::queryComputationResultCallback ( choreo_msgs::QueryComputationRecord::Request &  req,
choreo_msgs::QueryComputationRecord::Response &  res 
)
private

Definition at line 450 of file choreo_core_service.cpp.

void ChoreoCoreService::run ( )

Definition at line 156 of file choreo_core_service.cpp.

void ChoreoCoreService::saveModelInputParameters ( const std::string &  filename)
private

Definition at line 190 of file choreo_core_service.cpp.

void ChoreoCoreService::saveOutputSaveDirInputParameters ( const std::string &  filename)
private

Definition at line 259 of file choreo_core_service.cpp.

void ChoreoCoreService::saveRobotInputParameters ( const std::string &  filename)
private

Definition at line 236 of file choreo_core_service.cpp.

void ChoreoCoreService::saveTaskSequenceInputParameters ( const std::string &  filename)
private

Definition at line 213 of file choreo_core_service.cpp.

void ChoreoCoreService::simulateMotionPlansActionCallback ( const choreo_msgs::SimulateMotionPlanGoalConstPtr &  goal_in)
private

Definition at line 712 of file choreo_core_service.cpp.

void ChoreoCoreService::taskSequencePlanningActionCallback ( const choreo_msgs::TaskSequencePlanningGoalConstPtr &  goal)
private

Definition at line 548 of file choreo_core_service.cpp.

void ChoreoCoreService::taskSequenceProcessingActionCallback ( const choreo_msgs::TaskSequenceProcessingGoalConstPtr &  goal)
private

Definition at line 464 of file choreo_core_service.cpp.

bool ChoreoCoreService::visualizeSelectedPathServerCallback ( choreo_msgs::VisualizeSelectedPath::Request &  req,
choreo_msgs::VisualizeSelectedPath::Response &  res 
)
private

Definition at line 374 of file choreo_core_service.cpp.

Member Data Documentation

choreo_msgs::AssemblySequencePickNPlace ChoreoCoreService::as_pnp_
private

Definition at line 170 of file choreo_core_service.h.

std::string ChoreoCoreService::assembly_type_
private

Definition at line 194 of file choreo_core_service.h.

actionlib::SimpleActionClient<choreo_msgs::ProcessExecutionAction> ChoreoCoreService::choreo_exe_client_
private

Definition at line 157 of file choreo_core_service.h.

ros::ServiceServer ChoreoCoreService::choreo_parameters_server_
private

Definition at line 115 of file choreo_core_service.h.

choreo_msgs::ModelInputParameters ChoreoCoreService::default_model_input_params_
private

Definition at line 183 of file choreo_core_service.h.

choreo_msgs::OutputSaveDirInputParameters ChoreoCoreService::default_output_save_dir_input_params_
private

Definition at line 186 of file choreo_core_service.h.

choreo_msgs::RobotInputParameters ChoreoCoreService::default_robot_input_params_
private

Definition at line 185 of file choreo_core_service.h.

choreo_msgs::TaskSequenceInputParameters ChoreoCoreService::default_task_sequence_input_params_
private

Definition at line 184 of file choreo_core_service.h.

ros::ServiceServer ChoreoCoreService::element_number_sequest_server_
private

Definition at line 116 of file choreo_core_service.h.

std::vector<moveit_msgs::CollisionObject> ChoreoCoreService::env_objs_
private

Definition at line 164 of file choreo_core_service.h.

ros::ServiceServer ChoreoCoreService::get_available_process_plans_server_
private

Definition at line 118 of file choreo_core_service.h.

choreo_msgs::ModelInputParameters ChoreoCoreService::model_input_params_
private

Definition at line 178 of file choreo_core_service.h.

ros::ServiceClient ChoreoCoreService::move_to_pose_client_
private

Definition at line 126 of file choreo_core_service.h.

ros::NodeHandle ChoreoCoreService::nh_
private

Definition at line 130 of file choreo_core_service.h.

ros::ServiceServer ChoreoCoreService::output_process_plans_server_
private

Definition at line 119 of file choreo_core_service.h.

ros::ServiceClient ChoreoCoreService::output_processing_client_
private

Definition at line 127 of file choreo_core_service.h.

choreo_msgs::OutputSaveDirInputParameters ChoreoCoreService::output_save_dir_input_params_
private

Definition at line 181 of file choreo_core_service.h.

std::string ChoreoCoreService::param_cache_prefix_
private

Definition at line 191 of file choreo_core_service.h.

ros::ServiceClient ChoreoCoreService::process_planning_client_
private

Definition at line 125 of file choreo_core_service.h.

choreo_msgs::ProcessPlanningFeedback ChoreoCoreService::process_planning_feedback_
private

Definition at line 140 of file choreo_core_service.h.

choreo_msgs::ProcessPlanningResult ChoreoCoreService::process_planning_result_
private

Definition at line 141 of file choreo_core_service.h.

actionlib::SimpleActionServer<choreo_msgs::ProcessPlanningAction> ChoreoCoreService::process_planning_server_
private

Definition at line 139 of file choreo_core_service.h.

ros::ServiceServer ChoreoCoreService::query_computation_result_server_
private

Definition at line 120 of file choreo_core_service.h.

choreo_msgs::RobotInputParameters ChoreoCoreService::robot_input_params_
private

Definition at line 180 of file choreo_core_service.h.

bool ChoreoCoreService::save_data_
private

Definition at line 189 of file choreo_core_service.h.

std::string ChoreoCoreService::save_location_
private

Definition at line 190 of file choreo_core_service.h.

int ChoreoCoreService::selected_task_id_
private

Definition at line 173 of file choreo_core_service.h.

choreo_msgs::SimulateMotionPlanFeedback ChoreoCoreService::simulate_motion_plan_feedback_
private

Definition at line 153 of file choreo_core_service.h.

choreo_msgs::SimulateMotionPlanResult ChoreoCoreService::simulate_motion_plan_result_
private

Definition at line 154 of file choreo_core_service.h.

actionlib::SimpleActionServer<choreo_msgs::SimulateMotionPlanAction> ChoreoCoreService::simulate_motion_plan_server_
private

Definition at line 143 of file choreo_core_service.h.

std::vector<choreo_msgs::ElementCandidatePoses> ChoreoCoreService::task_sequence_
private

Definition at line 167 of file choreo_core_service.h.

choreo_msgs::TaskSequenceInputParameters ChoreoCoreService::task_sequence_input_params_
private

Definition at line 179 of file choreo_core_service.h.

choreo_msgs::TaskSequencePlanningFeedback ChoreoCoreService::task_sequence_planning_feedback_
private

Definition at line 136 of file choreo_core_service.h.

choreo_msgs::TaskSequencePlanningResult ChoreoCoreService::task_sequence_planning_result_
private

Definition at line 137 of file choreo_core_service.h.

actionlib::SimpleActionServer<choreo_msgs::TaskSequencePlanningAction> ChoreoCoreService::task_sequence_planning_server_
private

Definition at line 135 of file choreo_core_service.h.

ros::ServiceClient ChoreoCoreService::task_sequence_planning_srv_client_
private

Definition at line 124 of file choreo_core_service.h.

choreo_msgs::TaskSequenceProcessingFeedback ChoreoCoreService::task_sequence_processing_feedback_
private

Definition at line 132 of file choreo_core_service.h.

choreo_msgs::TaskSequenceProcessingResult ChoreoCoreService::task_sequence_processing_result_
private

Definition at line 133 of file choreo_core_service.h.

actionlib::SimpleActionServer<choreo_msgs::TaskSequenceProcessingAction> ChoreoCoreService::task_sequence_processing_server_
private

Definition at line 131 of file choreo_core_service.h.

ros::ServiceClient ChoreoCoreService::task_sequence_processing_srv_client_
private

Definition at line 123 of file choreo_core_service.h.

choreo_core_service::TrajectoryLibrary ChoreoCoreService::trajectory_library_
private

Definition at line 175 of file choreo_core_service.h.

bool ChoreoCoreService::use_saved_graph_
private

Definition at line 174 of file choreo_core_service.h.

choreo_visual_tools::ChoreoVisualTools ChoreoCoreService::visual_tools_
private

Definition at line 160 of file choreo_core_service.h.

ros::ServiceServer ChoreoCoreService::visualize_selected_path_server_
private

Definition at line 117 of file choreo_core_service.h.

std::string ChoreoCoreService::world_frame_
private

Definition at line 192 of file choreo_core_service.h.


The documentation for this class was generated from the following files:


choreo_core
Author(s): Yijiang Huang
autogenerated on Thu Jul 18 2019 03:59:38