From c56b427e47259d63ffae1e8a9bbf453da4afedb2 Mon Sep 17 00:00:00 2001 From: Emanuele Date: Mon, 28 Oct 2019 11:43:39 +0100 Subject: [PATCH] =?UTF-8?q?Invio=20delle=20traiettorie=20in=20pi=C3=B9=20s?= =?UTF-8?q?egmenti?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Funzionante con il nuovo controller --- src/roboglue_ros/config/meta/test09.meta | 2 +- src/roboglue_ros/src/roboglue_recorder.cpp | 5 ++++- 2 files changed, 5 insertions(+), 2 deletions(-) diff --git a/src/roboglue_ros/config/meta/test09.meta b/src/roboglue_ros/config/meta/test09.meta index b883db0..900f00b 100644 --- a/src/roboglue_ros/config/meta/test09.meta +++ b/src/roboglue_ros/config/meta/test09.meta @@ -1 +1 @@ -{"code":"{846e5f31-1384-437f-bfd3-e7c49b8adc9a}","ds":100.0,"dt":0.5,"frame_base":"---","frame_work":{"name":"---","offset":{"r":0.0,"x":0.0,"y":0.0,"z":0.0}},"n_analog":0,"n_digital":0,"n_point":270,"name":"test09","type":"time/dist"} +{"code":"{846e5f31-1384-437f-bfd3-e7c49b8adc9a}","ds":2.0,"dt":0.5,"frame_base":"---","frame_work":{"name":"---","offset":{"r":0.0,"x":0.0,"y":0.0,"z":0.0}},"n_analog":0,"n_digital":0,"n_point":270,"name":"test09","type":"time/dist"} diff --git a/src/roboglue_ros/src/roboglue_recorder.cpp b/src/roboglue_ros/src/roboglue_recorder.cpp index c0d4a72..4738a38 100644 --- a/src/roboglue_ros/src/roboglue_recorder.cpp +++ b/src/roboglue_ros/src/roboglue_recorder.cpp @@ -347,6 +347,9 @@ int main(int argc, char **argv) { tempPlanningVector.back().header.frame_id="/world"; } //TODO sincronizzazione delle uscite ausiliarie con il movimento del robot!!! + //TODO l'invio di traiettorie segmentato in più esecuzioni funziona + // si potrebbe quindi sincronizzare l'attivazione delle uscite ausiliarie ad ogni invio di nuova traiettoria + // select right planner if (!robot_data.planning_mode.compare("path")){ const double jmp_thr= 0.00; @@ -362,7 +365,7 @@ int main(int argc, char **argv) { move_group.setStartStateToCurrentState(); move_group.computeCartesianPath(pss,ee_step,jmp_thr,traj, false, &ec); ROS_DEBUG("Trajectory Compute ExitCode: %d",ec.val); -// BUG il controllo del salto dei giunti crasha il nodo. +// BUG: il controllo del salto dei giunti crasha il nodo. // if (checkJointJump(boost::shared_ptr(&traj), 90.0)){ // ROS_WARN("Joint Jump Detected!!!"); // }