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

[MoveIt!] How to Use the Python Move Group Interface

asked 2016-08-08 12:16:44 -0500

F4bich gravatar image

Hi,

I want to use MoveIt! for pathfinding for a simple manipulator arm. The MoveIt! Setup Assistant and Rviz Integration tutorials were very helpful for the first usage of MoveIt! with the manipulator arm.

So far I can calculate paths between predefined poses using the Motion Planning extension. for Rviz

However, I now want to want to define a point in cartesian space. MoveIt! should then calculate a fitting manipulator pose itself and present a possible path from the current pose to the goal if there exists one.

I figured that this should be possible through the Move Group Interface of MoveIt! which I would then like to use with Python. This tutorial coveres this problem, I think. But I have no idea how to implement this for my own robot simulation.

Could someone explain me the steps that need to be done to transfer the tutorial on a different robot?

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
1

answered 2016-08-08 17:59:20 -0500

Chickenman gravatar image

Hi

I am not very skilled with python but I am using move_group with c++. For implementig that tutorial on your robot. You just need to change this command.

group = moveit_commander.MoveGroupCommander("left_arm")

Instead of "left_arm" you should put name of your planning group which you specified in moveit_setup_assistant Next important thing is to change desired goal to the real position which could your manipulator really reach.

pose_target = geometry_msgs.msg.Pose()
pose_target.orientation.w = 1.0
pose_target.position.x = 0.7
pose_target.position.y = -0.05
pose_target.position.z = 1.1
group.set_pose_target(pose_target)

Remember as it was mentioned in tutorial trajectory will be just planned and not executed

Whole code could be found here https://github.com/ros-planning/movei...

When you will running code remember that your move_group should be running.

edit flag offensive delete link more

Comments

Thanks for the answer. Is my move_group running when I visualize the manipulator using Rviz? So I would then only have to use: $ rosrun myscript.py To execute the script?

I get errors saying that the topic shut down unexpected, when I do this.

F4bich gravatar image F4bich  ( 2016-08-09 03:01:58 -0500 )edit

your move group should be running when you call

roslaunch robot_moveit_config demo.launch

"robot_moveit_config" is name of your package you setuped in setup_assistant. If it still does not work you can send me your "robot_moveit_config" and I could try to move robot on my own using python

Chickenman gravatar image Chickenman  ( 2016-08-09 18:29:40 -0500 )edit

Question Tools

Stats

Asked: 2016-08-08 12:16:44 -0500

Seen: 3,030 times

Last updated: Aug 08 '16