diff --git a/tesseract_monitoring/include/tesseract_monitoring/constants.h b/tesseract_monitoring/include/tesseract_monitoring/constants.h index 9ca4570b..c3baec81 100644 --- a/tesseract_monitoring/include/tesseract_monitoring/constants.h +++ b/tesseract_monitoring/include/tesseract_monitoring/constants.h @@ -25,6 +25,8 @@ #ifndef TESSERACT_MONITORING_CONSTANTS_H #define TESSERACT_MONITORING_CONSTANTS_H +#include + namespace tesseract_monitoring { /// The name of the topic used by default for receiving joint states diff --git a/tesseract_msgs/msg/PlanningRequest.msg b/tesseract_msgs/msg/PlanningRequest.msg index ea744fc3..c1dcb2f3 100644 --- a/tesseract_msgs/msg/PlanningRequest.msg +++ b/tesseract_msgs/msg/PlanningRequest.msg @@ -3,7 +3,7 @@ tesseract_msgs/EnvironmentCommand[] commands # Additional Commands to be applied string name # The name of the taskflow to use string executor # The executor to leverage, if empty default one is used. -string instructions # This should an xml string of the command language instructions +string input # This should be an xml string of tesseract_common::AnyPoly bool dotgraph # Enable if DOT Graph should be generated and returned bool debug # Enable debug content bool save_io # Enable saving of input and output for task infos diff --git a/tesseract_planning_server/src/tesseract_planning_server.cpp b/tesseract_planning_server/src/tesseract_planning_server.cpp index d55faf77..3ffa7f18 100644 --- a/tesseract_planning_server/src/tesseract_planning_server.cpp +++ b/tesseract_planning_server/src/tesseract_planning_server.cpp @@ -56,7 +56,7 @@ TESSERACT_COMMON_IGNORE_WARNINGS_POP #include -#include +#include #include #include @@ -67,7 +67,6 @@ using tesseract_common::Serialization; using tesseract_planning::InstructionPoly; using tesseract_planning::PlanningTaskComposerProblem; using tesseract_planning::TaskComposerDataStorage; -using tesseract_rosutils::processMsg; static const std::string TRAJOPT_DEFAULT_NAMESPACE = "TrajOptMotionPlannerTask"; static const std::string TRAJOPT_IFOPT_DEFAULT_NAMESPACE = "TrajOptIfoptMotionPlannerTask"; @@ -206,8 +205,7 @@ void TesseractPlanningServer::onMotionPlanningCallback( auto problem = std::make_unique(goal->request.name); try { - problem->input_instruction = - Serialization::fromArchiveStringXML(goal->request.instructions); + problem->input = Serialization::fromArchiveStringXML(goal->request.input); } catch (const std::exception& e) {