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

MOVEIT PROBLEM -> Fail: ABORTED: No motion plan found. No execution attempted

asked 2020-01-06 14:05:26 -0500

Aaron MV gravatar image

HI! everyone ! I'm using MOVEIT in ROS KINETIC and i traying to learn more about it with MOVEIT C++ API,

i had the follow error . Fail: ABORTED: No motion plan found. No execution attempted

I was programming two programs, the first execute a random trajectory and works fine : CODE:

#include <ros/ros.h>
//MOVE IT 
#include <moveit/move_group_interface/move_group_interface.h>

int main(int argc, char **argv){

  ros::init(argc,argv,"moveit_group_goal");
  ros::AsyncSpinner spinner(1);
  spinner.start();

//Connects to a running instance of the move_group node
  moveit::planning_interface::MoveGroupInterface group("arm");
//Create a random Trajectory

  group.setRandomTarget();
//Plan the motion and then move the group to the sampled target
  group.move();


  ros::waitForShutdown();
  return 0;
}

Then i m run the following command in other terminal to check a valid state :

 rosrun moveit_commander moveit_commander_cmdline.py

And the result its :

pose: 
  position: 
    x: -0.0494107529521
    y: -0.0346919771955
    z: 1.03358551516
  orientation: 
    x: 0.807794454316
    y: 0.0
    z: 0.0
    w: 0.589464264885 ]

The second one node that i was program its a custom planning :

#include <ros/ros.h>
//MOVE IT
#include <moveit/planning_scene_interface/planning_scene_interface.h>
#include <moveit/move_group_interface/move_group_interface.h>
#include <moveit_msgs/DisplayTrajectory.h>
#include <moveit_msgs/DisplayRobotState.h>
#include <moveit_msgs/AttachedCollisionObject.h>
#include <moveit_msgs/CollisionObject.h>
#include <moveit/robot_model_loader/robot_model_loader.h>
#include <moveit/robot_model/robot_model.h>
#include <moveit/robot_state/robot_state.h>

ros::Publisher display_publisher;

int main(int argc, char **argv)
{

ros::init(argc, argv, "custom_planning");
ros::NodeHandle nh;
ros::AsyncSpinner spinner(1);
spinner.start();
sleep(2.0);



//planning group that we would like to control
moveit::planning_interface::MoveGroupInterface group("arm");
//we can add or remove collision objects in our virtual world scene
moveit::planning_interface::PlanningSceneInterface planning_scene_interface;
//raw pointers are used to refer to the planning group for improved performance
const robot_state::JointModelGroup* joint_model_group = group.getCurrentState()->getJointModelGroup("arm");
group.setEndEffectorLink("link3");
group.setPoseReferenceFrame("world");
group.setPlannerId("RRTstar");
group.setNumPlanningAttempts(10);
group.setPlanningTime(10.0);
group.allowReplanning(true);
group.setGoalJointTolerance(0.0001);
group.setGoalPositionTolerance(0.0001);
group.setGoalOrientationTolerance(0.001);
group.setNamedTarget("random");
group.move();  // WORKS FINE :)
sleep(5.0);

//  CUSTOM PLANNING
geometry_msgs::Pose target_pose1;
//NOTE: THIS IS THE VALID POSE FROM RANDOM NODE   
target_pose1.orientation.w = 0.589464264885;
target_pose1.orientation.x = 0.807794454316;
target_pose1.orientation.y = 0;
target_pose1.orientation.z = 0;
target_pose1.position.x =  -0.0494107529521;
target_pose1.position.y =  -0.0346919771955;
target_pose1.position.z =  1.03358551516;

 group.setStartStateToCurrentState();
 group.setPoseTarget(target_pose1,"link3");

moveit::planning_interface::MoveGroupInterface::Plan my_plan;
moveit_msgs::MotionPlanRequest response;

group.plan(my_plan);
group.execute(my_plan);

sleep(5.0);
ros::shutdown();

return 0;
}

And works fine for RANDOM TARGET, but well when custom planning is executed, its give me the below error

 [WARN] [1578340196.576932864]: Fail: ABORTED: No motion plan found. No execution attempted.

I don't now why this error occurs , its any one can help me please?

I'm searched in many forums and i cant found nothing for my error , i hope you can help me

Regards!

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
2

answered 2020-01-07 07:27:13 -0500

Aaron MV gravatar image

updated 2020-01-07 07:27:53 -0500

HI! finally i'm solve my problem change this line

 group.setPoseTarget(target_pose1,"link3");

for this

 group.setApproximateJointValueTarget(target_pose1, "link3");

if anyone have other solution plz let me now!

thank's anyway :)

edit flag offensive delete link more

Comments

I tried to increase the number of attempts and the planning time, it provides solutions but it has a high tolerance

group.setNumPlanningAttempts(50);

group.setPlanningTime(50.0);

Moneera Banjar gravatar image Moneera Banjar  ( 2021-01-30 14:21:13 -0500 )edit
1

I increased the tolerance of position and orientation, it finally can provide solutions but the final position and orientation is different from what I set

Alice_ly gravatar image Alice_ly  ( 2021-04-30 08:58:00 -0500 )edit

Question Tools

Stats

Asked: 2020-01-06 14:05:26 -0500

Seen: 2,044 times

Last updated: Jan 07 '20