ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

Move Cartesian with MoveIt

asked 2019-02-27 01:53:06 -0500

MarkusHHN gravatar image

updated 2019-02-28 00:53:54 -0500

Hello,

i would like to move the robot "Franka Emika Panda" with the cartesian movement in C++. I make the configuration which is recommended on the homepage. My current result is to move the robot with joint movement with moveit. Then I trying the cartesian movement with the following link:

http://docs.ros.org/kinetic/api/movei...

In this section they show how it works with the simulation, but i would like to try this one on the real robot. I hope i can get some tips to solve my problem.

EDIT: I add the source code and the launch-file which i use.

SOURCE CODE

//Cartesian Path
geometry_msgs::Pose target_pose3 = move_group.getCurrentPose().pose;

std::cout<< "Anfangsposition" << std::endl;
std::cout<< target_pose3 << std::endl;

std::vector<geometry_msgs::Pose> waypoints;
waypoints.push_back(target_pose3);

target_pose3.position.z -= 0.2;
waypoints.push_back(target_pose3); //down

target_pose3.position.y -= 0.2;
waypoints.push_back(target_pose3); //right

target_pose3.position.z += 0.2;
target_pose3.position.y += 0.2;
target_pose3.position.x -= 0.2;
waypoints.push_back(target_pose3);

// Skalierungsfaktor der maximalen Geschwindigkeit jedes Gelenks
move_group.setMaxVelocityScalingFactor(0.1);

moveit_msgs::RobotTrajectory trajectory;
const double jump_threshold = 0.5;
const double eef_step = 0.01;
move_group.computeCartesianPath(waypoints, eef_step, jump_threshold, trajectory);

moveit::planning_interface::MoveGroupInterface::Plan goal_plan;
goal_plan.trajectory_ = trajectory;
move_group.execute(goal_plan);

LAUNCH-FILE

<?xml version="1.0" ?>
<launch>
    <arg name="robot_ip" />

    <include file="$(find franka_control)/launch/franka_control.launch">
        <arg name="robot_ip" value="172.16.0.2" />
        <arg name="load_gripper" value="false" />
    </include>
    <include file="$(find panda_moveit_config)/launch/panda_moveit.launch">
         <arg name="load_gripper" value="false" />
    </include>
</launch>

When i start my source code then i get some information back from the console

 INFO] [1551336690.500652276]: Received request to compute Cartesian path
[ INFO] [1551336690.501040209]: Attempting to follow 4 waypoints for link 'panda_link8' using a step of 0.010000 m and jump threshold 0.500000 (in global reference frame)
[ INFO] [1551336690.507374299]: Computed Cartesian path with 2 points (followed 2.597403% of requested trajectory)
[ INFO] [1551336690.508019615]: Execution request received
[ WARN] [1551336690.534495590]: Dropping first 1 trajectory point(s) out of 2, as they occur before the current time.
First valid point will be reached in 0.013s.
[ INFO] [1551336690.667268099]: Completed trajectory execution with status SUCCEEDED ...
[ INFO] [1551336690.667388163]: Execution completed: SUCCEEDED

Regards, Markus

edit retag flag offensive close merge delete

Comments

You should always visually inspect the generated plan before executing on hardware. The computeCartesianPath functionality has a known issue that could result in joint flips.

mlautman gravatar image mlautman  ( 2019-03-05 15:12:30 -0500 )edit

thank you for the information. It is possible to solve or improve this problem?

MarkusHHN gravatar image MarkusHHN  ( 2019-03-06 00:28:20 -0500 )edit

2 Answers

Sort by ยป oldest newest most voted
1

answered 2019-02-27 08:12:48 -0500

aPonza gravatar image

If I understand your question correctly, you probably just need to create/update a plan using the trajectory which is I/O in computeCartesianPath, and then call MoveGroup::execute with said path.

Assuming the tutorial's notation, this should work:

my_plan.trajectory_ = trajectory;
move_group.execute(my_plan);
edit flag offensive delete link more

Comments

Thank you for your answer, but the robot dont moving to this position. I will add some source code and information

MarkusHHN gravatar image MarkusHHN  ( 2019-02-28 00:46:17 -0500 )edit
0

answered 2019-02-28 01:07:31 -0500

MarkusHHN gravatar image

I find the problem:

moveit_msgs::RobotTrajectory trajectory;
const double jump_threshold = 0.5; 
const double eef_step = 0.01;
move_group.computeCartesianPath(waypoints, eef_step, jump_threshold, trajectory);

The solution ist to set the jump_threshold to 0.0. Then the robot start to move without issues.

edit flag offensive delete link more

Question Tools

2 followers

Stats

Asked: 2019-02-27 01:53:06 -0500

Seen: 2,694 times

Last updated: Feb 28 '19