Skip to content

Commit 570b39d

Browse files
committed
Compiler and functional tweaks for MoveIt jazzy
1 parent 9dedfff commit 570b39d

File tree

1 file changed

+8
-7
lines changed

1 file changed

+8
-7
lines changed

clr_pick_and_place_demo/src/run_demo.cpp

Lines changed: 8 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -22,8 +22,9 @@
2222
#include <map>
2323
#include <thread>
2424

25-
#include <moveit/move_group_interface/move_group_interface.h>
26-
#include <moveit/trajectory_processing/iterative_time_parameterization.h>
25+
#include <moveit/move_group_interface/move_group_interface.hpp>
26+
#include <moveit/trajectory_processing/time_optimal_trajectory_generation.hpp>
27+
#include <moveit/utils/moveit_error_code.h>
2728
#include <moveit_visual_tools/moveit_visual_tools.h>
2829
#include <moveit_msgs/msg/allowed_collision_matrix.hpp>
2930
#include <moveit_msgs/srv/apply_planning_scene.hpp>
@@ -728,10 +729,10 @@ class RunDemoNode : public rclcpp::Node
728729
// The page below is referenced, which recommends manual velocity scaling:
729730
// https://groups.google.com/g/moveit-users/c/MOoFxy2exT4
730731

731-
trajectory_processing::IterativeParabolicTimeParameterization iptp;
732+
trajectory_processing::TimeOptimalTrajectoryGeneration totg;
732733

733734
bool success;
734-
success = iptp.computeTimeStamps(rt, scaling, scaling);
735+
success = totg.computeTimeStamps(rt, scaling, scaling);
735736
RCLCPP_INFO(LOGGER, "Computed time stamp %s", success ? "SUCCEEDED" : "FAILED");
736737

737738
if (success)
@@ -786,12 +787,12 @@ class RunDemoNode : public rclcpp::Node
786787
if (error_code == moveit::core::MoveItErrorCode::SUCCESS)
787788
{
788789
RCLCPP_INFO(LOGGER, "Successfully computed trajectory");
789-
trajectory = plan.trajectory_;
790+
trajectory = plan.trajectory;
790791
return true;
791792
}
792793
else
793794
{
794-
RCLCPP_ERROR(LOGGER, "Planning failed with error code %s", error_code_to_string(error_code).c_str());
795+
RCLCPP_ERROR(LOGGER, "Planning failed with error code %s", error_code.message.c_str());
795796
return false;
796797
}
797798
}
@@ -801,7 +802,7 @@ class RunDemoNode : public rclcpp::Node
801802
moveit::core::MoveItErrorCode move_success = move_group->execute(trajectory);
802803
if (move_success != moveit::core::MoveItErrorCode::SUCCESS)
803804
{
804-
error_code_to_string(move_success);
805+
RCLCPP_ERROR(LOGGER, "Execution failed with error code %s", move_success.message.c_str());
805806
return false;
806807
}
807808
return true;

0 commit comments

Comments
 (0)