Skip to content

Commit aae6975

Browse files
committed
More updates
1 parent 59accb1 commit aae6975

File tree

1 file changed

+2
-3
lines changed

1 file changed

+2
-3
lines changed

clr_pick_and_place_demo/src/run_demo.cpp

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

25-
#include <moveit/utils/moveit_error_code.h>
25+
#include <moveit/utils/moveit_error_code.hpp>
2626
#include <moveit_visual_tools/moveit_visual_tools.h>
2727
#include <moveit/move_group_interface/move_group_interface.hpp>
2828
#include <moveit/trajectory_processing/time_optimal_trajectory_generation.hpp>
@@ -702,10 +702,9 @@ class RunDemoNode : public rclcpp::Node
702702
RCLCPP_INFO(LOGGER, "End effector link: %s", move_group->getEndEffectorLink().c_str());
703703
RCLCPP_INFO(LOGGER, "Using planning group: %s", move_group->getName().c_str());
704704

705-
const double jump_threshold = 0.0;
706705
const double eef_step = 0.01;
707706

708-
double trajectory_percent = move_group->computeCartesianPath(poses, eef_step, jump_threshold, trajectory);
707+
double trajectory_percent = move_group->computeCartesianPath(poses, eef_step, trajectory);
709708

710709
if (trajectory_percent == 1.0)
711710
{

0 commit comments

Comments
 (0)