Moveit Path Planning Not Respecting Collision Objects

asked 2018-07-11 12:42:21 -0500

jbeck28 gravatar image

I'm running ROS Kinetic on Ubuntu 16.04, and I'm attempting to bring collision objects into my planning scene in moveit. I've written a class on top of moveit visual tools to allow for attaching collision meshes. Although the collision objects visibly appear in the planning scene, the arm regularly comes in contact with the part without error. However, in RVIZ, under the Scene Objects tab, if I press "Publish Scene", and replan the path, the collisions are detected. If I echo the topic to "move_group/monitored_planning_scene", the messages are sent when that button is pressed, and when I run my program... so I'm not certain what functionality is provided by the Publish Scene button that isn't provided by my program.

Here's the code for my class:

visual_tools::visual_tools(){

    visual_tools_.reset(new moveit_visual_tools::MoveItVisualTools("base_link","moveit_visual_tools",planning_scene_monitor_));
    visual_tools_->setPlanningSceneTopic("/move_group/monitored_planning_scene");
    visual_tools_->loadPlanningSceneMonitor();


    visual_tools_->loadMarkerPub(true);
    visual_tools_->setManualSceneUpdating();
    robot_state_ = visual_tools_->getSharedRobotState();
    jmg_ = robot_state_->getJointModelGroup("manipulator");
    ros::spinOnce();
}
void visual_tools::attachMesh(Eigen::Affine3d pose, std::string object_name, std::string filePath, rviz_visual_tools::colors color){
    visual_tools_->publishCollisionMesh(pose,object_name,filePath,color);
    visual_tools_->triggerPlanningSceneUpdate();
    ros::spinOnce();
}

The specific code which instantiates this class is as follows:

optimax::visual_tools test;
std::string tableLoc = "package://abb_irb2400_deflectometry_support/meshes/scene/KB05.STL";
std::string partLoc  = "package://abb_irb2400_deflectometry_support/meshes/scene/AF_Window_CC.STL";
Eigen::Affine3d tablepose = Eigen::Affine3d::Identity();
test.attachMesh(tablepose,"table",tableLoc,rviz_visual_tools::colors::BLUE);
test.attachMesh(toolpath.UFtransform,"part",partLoc,rviz_visual_tools::colors::GREY);

Any help in determining where the issue lies would be much appreciated!!

edit retag flag offensive close merge delete