Skip to content

Commit

Permalink
Fix deprecated computeCartesianPath()
Browse files Browse the repository at this point in the history
  • Loading branch information
rhaschke committed Aug 29, 2024
1 parent b694b64 commit 6ce67d1
Showing 1 changed file with 1 addition and 2 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -301,9 +301,8 @@ int main(int argc, char** argv)
// Warning - disabling the jump threshold while operating real hardware can cause
// large unpredictable motions of redundant joints and could be a safety issue
moveit_msgs::RobotTrajectory trajectory;
const double jump_threshold = 0.0;
const double eef_step = 0.01;
double fraction = move_group_interface.computeCartesianPath(waypoints, eef_step, jump_threshold, trajectory);
double fraction = move_group_interface.computeCartesianPath(waypoints, eef_step, trajectory);
ROS_INFO_NAMED("tutorial", "Visualizing plan 4 (Cartesian path) (%.2f%% achieved)", fraction * 100.0);

// Visualize the plan in RViz
Expand Down

6 comments on commit 6ce67d1

@AmirpooyaSh
Copy link

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Hello @rhaschke

I believe that this commit seems not compatible with the MoveIt tutorials given in the documentation:
https://moveit.github.io/moveit_tutorials/doc/getting_started/getting_started.html

I assume that the header file updates have not been committed yet.
Bringing it back to what it was solved my issue in building the moveit tutorial package.

@rhaschke
Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Did you build against latest source of MoveIt?

@AmirpooyaSh
Copy link

@AmirpooyaSh AmirpooyaSh commented on 6ce67d1 Sep 14, 2024

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I just cloned the master branch (for tutorials) according to the given tutorials:

git clone https://github.com/moveit/moveit_tutorials.git -b master

for the MoveIt library, no. I just installed it through the terminal command (it might not be the latest version).

@rhaschke
Copy link
Contributor Author

@rhaschke rhaschke commented on 6ce67d1 Sep 16, 2024

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The tutorials suggest downloading and building MoveIt from source as well. If you do, you will need the changes here.
A new release of MoveIt has been made. It will become publicly available with the next sync.

@addy1997
Copy link

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@rhaschke, I am getting error related to the computeCartesianPath function after running catkin build on my moveit workspace

Error:

Image

I have followed all the build instructions exactly. Could you suggest something?

@rhaschke
Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@addy1997: you don't build MoveIt from source, but use the installation in /opt/ros/noetic.

Please sign in to comment.