MoveIt, ultraArm P340: planning to specific position not working

asked 2023-04-19 03:48:11 -0500

Luzgar gravatar image

updated 2023-05-24 02:59:38 -0500

gvdhoorn gravatar image

I purchased a robot arm (ultraArm P340) but I can not get the motion planning to work for a target position or pose when using a ROS node to make a motion planning request. They provide ROS packages for most of their robots on a github repo : https://github.com/elephantrobotics/m... They provide detailed installations instructions for ROS and moveit that I followed : https://docs.elephantrobotics.com/doc...

I had never used ROS before this project, but after 2 weeks learning about it and trying to get it to work, I think that I have a good understanding of what is going on.

Most functionality are working :

  • motion planning in Rviz using roslaunch ultraarm_moveit demo.launch
  • Using the moveit_commander python library for : motion planning to a named target or motion planning a set a joint angles

But trying to get motion planning using moveit_commander to a target pose or position always produces the exact same error :

moveit_commander node :

[ INFO] [1681738300.806735145]: Loading robot model 'firefighter'...
[ INFO] [1681738302.128773583]: Ready to take commands for planning group arm_group.
[ WARN] [1681738310.053679700]: Fail: ABORTED: TIMED_OUT

Code :

I based my code on this example : https://github.com/ros-planning/movei... I also tried the script rosrun ultraarm_moveit path_planning_and_obstacle_avoidance_demo.py that they provide, but it seems to be broken in multiple ways.

Some parts are working fine :

  • move_group.go(joint_goal, wait=True)
  • move_group.set_named_target("init_pose")

But other refuse to work, despite the many different pose and position goal I tried (including going to the current position). Target position :

move_group.set_position_target([0.03, 0, 0.3]) #Very close to the current home position
success = move_group.go(wait=True)

Target pose :

current_pose = move_group.get_current_pose()
move_group.set_pose_target(current_pose)
success = move_group.go(wait=True)

(Creating a pose and specifying a position like in the base example did not work any better.)

ultraArm_moveit.launch :

[ INFO] [1681741002.222114463]: Ready to take commands for planning group arm_group.
[ INFO] [1681741013.471013449]: Combined planning and execution request received for MoveGroup action. Forwarding to planning and execution pipeline.
[ INFO] [1681741013.471172510]: Planning attempt 1 of at most 1
[ INFO] [1681741013.475019385]: Planner configuration 'arm_group' will use planner 'geometric::RRTConnect'. Additional configuration parameters will be set when the planner is constructed.
[ INFO] [1681741013.475940740]: arm_group/arm_group: Starting planning with 1 states already in datastructure
[ERROR] [1681741018.478799338]: arm_group/arm_group: Unable to sample any valid states for goal tree
[ INFO] [1681741018.479120936]: arm_group/arm_group: Created 1 states (1 start + 0 goal)
[ INFO] [1681741018.479382594]: No solution found after 5.003575 seconds
[ WARN] [1681741018.479508336]: Timed out
[ INFO] [1681741018.491237496]: Unable to solve the planning problem

Config :

ROS : noetic (latest version using binary install) Moveit : ros-noetic-moveit (1.1.11-1focal.20230413.061933) (latest version using binary install) OS : 20.04.6 LTS (Focal Fossa) (Virtual box fresh install)

I have been trying for a long time to get this to work, and I have tried pretty much everything I could find, but I always get this exact error.

I also attempted to use the code they provide for ROS2 ... (more)

edit retag flag offensive close merge delete

Comments

Is there something wrong with my post, or out of the 210 persons that visited it, nobody has any idea of what might be going wrong ?

If you have a suggestion, please let me know.

Luzgar gravatar image Luzgar  ( 2023-05-23 10:52:08 -0500 )edit

I don't believe there is anything wrong necessarily. But sometimes it just happens that board members who might be able to provide any insight haven't seen your question. That's not because your question is being purposefully ignored, it's just bad luck. Could also be your question is "too localized", as in: there are too many details specific to your situation (ie: hw, sw, setup) which makes it difficult for anyone else to meaningfully say something about it.

Having written that: I don't believe your arm is 6 dof. Unless you've configured MoveIt (specifically: your IK solver) correctly for this, it typically isn't happy planning for your robot.

The fact joint (space) goals do work (and 'named poses' are essentially joint space goals) seems to point into the direction of IK problems as well.

Note: I'm not claiming IK is the cause here ...(more)

gvdhoorn gravatar image gvdhoorn  ( 2023-05-24 02:26:04 -0500 )edit

If this is your robot and the URDF your using, that would be a 3 dof robot. In my experience that will not work with KDL (which is the default IK solver).

You'd probably need to generate an IK solver with IKFast, using one of the 3 dof solver options. Or write one, or see whether other IK solvers do work (like TracIK, or BioIK).

It's possible RViz works because Elephant configured the MoveIt RViz plugin to enable "approximate IK solutions" (here). That is a work-around to allow a 6 dof pose to be solved for a < 6 dof kinematic configuration.

gvdhoorn gravatar image gvdhoorn  ( 2023-05-24 02:32:56 -0500 )edit