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

unable to move arm with moveit!

asked 2018-01-09 08:47:37 -0500

omer91 gravatar image

updated 2018-01-09 08:48:29 -0500

On kinetic, Ubuntu 16.04, trying to make the arm of my robot move a little bit.

the code:

bool run_script(){
    moveit::planning_interface::MoveGroupInterface move_group("arm");
    geometry_msgs::Pose target_pose1;
    target_pose1.orientation.w = 1.0;
    target_pose1.position.x = 0.28;
    target_pose1.position.y = -0.7;
    target_pose1.position.z = 1.0;
    move_group.setPoseTarget(target_pose1);

    move_group.move();
    return true;
}

The log:

[ INFO] [1515508915.187395653, 2305.704000000]: Combined planning and execution request received for MoveGroup action. Forwarding to planning and execution pipeline.
[ INFO] [1515508915.187550137, 2305.704000000]: Planning attempt 1 of at most 1
Debug:   Starting goal sampling thread
[ INFO] [1515508915.188247424, 2305.704000000]: Planner configuration 'arm' will use planner 'geometric::RRTConnect'. Additional configuration parameters will be set when the planner is constructed.
Debug:   The value of parameter 'longest_valid_segment_fraction' is now: '0.0050000000000000001'
Debug:   The value of parameter 'range' is now: '0'
Debug:   RRTConnect: Planner range detected to be 4.610440
Info:    RRTConnect: Starting planning with 1 states already in datastructure
Debug:   RRTConnect: Waiting for goal region samples ...
Debug:   Beginning sampling thread computation
Error:   RRTConnect: Unable to sample any valid states for goal tree
         at line 215 in /tmp/binarydeb/ros-kinetic-ompl-1.2.1/src/ompl/geometric/planners/rrt/src/RRTConnect.cpp
Info:    RRTConnect: Created 1 states (1 start + 0 goal)
Info:    No solution found after 5.007760 seconds
Debug:   Attempting to stop goal sampling thread...
Debug:   Stopped goal sampling thread after 0 sampling attempts
[ INFO] [1515508920.215263508, 2309.500000000]: Unable to solve the planning problem

I even tried getting the current pose and change it a little:

bool run_script(){
    moveit::planning_interface::MoveGroupInterface move_group("arm");
    geometry_msgs::PoseStamped pose1 = move_group.getCurrentPose();
    pose1.pose.position.x = pose1.pose.position.x + pose1.pose.position.x/4;
    move_group.setPoseTarget(pose1);

    move_group.move();
    return true;
}

If you need anymore info let me know.

edit retag flag offensive close merge delete

Comments

1

I am also facing same issue. However, i am able to move the arms using the joint angles though, only pose based movement is not working properly

dpakshimpo gravatar image dpakshimpo  ( 2018-03-15 05:48:19 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
0

answered 2018-08-19 21:35:07 -0500

fvd gravatar image

updated 2018-08-19 21:41:44 -0500

The error message "Unable to sample any valid state for goal tree" usually means that either there is a collision for the position you requested, or the position cannot be reached for whatever reason.

The most common error for this is that the orientation of your end effector pose is not what you expect it to be. Check that your start and goal poses are similar by publishing them using rviz_visual_tools:

#include <rviz_visual_tools/rviz_visual_tools.h>

rviz_visual_tools::RvizVisualToolsPtr visual_tools_;
visual_tools_.reset(new rviz_visual_tools::RvizVisualTools("world","/rviz_visual_markers"));
visual_tools_->publishAxis(pose_not_stamped);
visual_tools_->trigger();

(Don't forget to include rviz_visual_tools in your CMakeLists.txt and package.xml, and adding a MarkerArray subscribed to /rviz_visual_markers to your Rviz window.)

When debugging move_group.getCurrentPose(), it is wise to do a sanity check by outputting (or visualizing) the pose, or you might get mixed up between different frames of reference:

ROS_INFO_STREAM("PoseStamped ps in " << ps.header.frame_id << " is: " << ps.pose.position.x << ", " << ps.pose.position.y << ", " << ps.pose.position.z);

Note that setTargetPose() by default sets the target pose for the frame that is defined as the end of your kinematic chain or end effector for your robot. Which frame is it? What is its orientation? You can check in the srdf of your robot, by using the moveit_setup_assistant, by showing the TF frames in Rviz, or by using the getEndEffectorLink() function of the MoveGroupInterface.

Lastly, make sure you are not sending multiple conflicting goals to the robot. Check the getPoseTargets() and clearPoseTargets() functions of the MoveGroupInterface.

edit flag offensive delete link more

Question Tools

3 followers

Stats

Asked: 2018-01-09 08:47:37 -0500

Seen: 2,551 times

Last updated: Aug 19 '18