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

Revision history [back]

click to hide/show revision 1
initial version

I'll post what worked out for me.

1) inclusion of header such as these helped me get rid of error "class XYZ has no member named ABC"

#include <moveit_msgs/CollisionObject.h>
#include <moveit_msgs/PlanningScene.h>
#include "geometric_shapes/shape_operations.h"
#include "geometric_shapes/shapes.h"
#include "geometric_shapes/mesh_operations.h"

2) As mentioned by @aPonza, vector resizing and indexing plays the trick when you want to include multiple meshes in planning scene

3) Frame id should always be the frame you want to reference your collision object to

collision_objects[0].header.frame_id = "world";

4) There is another option to get this thing working, it is posted here

5) ros::sleep(duration) is necessary after below line in code or else RVIZ may miss out of visulizing collision object to planning scene but RVIZ will add the collision object to planning scene and it can be scene in motion planning plugin >> scene object tab in RVIZ.

planning_scene_interface.applyCollisionObjects(collision_vector)

Below is my full working code:

#include "ros/ros.h"
#include "moveit/move_group_interface/move_group_interface.h"
#include "moveit/planning_scene_interface/planning_scene_interface.h"
#include <moveit_msgs/CollisionObject.h>
#include <moveit_msgs/PlanningScene.h>
#include "geometric_shapes/shape_operations.h"
#include "geometric_shapes/shapes.h"
#include "geometric_shapes/mesh_operations.h"



int main(int argc, char **argv)
{
    ros::init(argc, argv, "attach_collision_objects");
    ros::NodeHandle node_handle;
    ros::AsyncSpinner spinner(1);
    spinner.start();

    //const std::string PLANNING_GROUP = "panda_arm";
    //moveit::planning_interface::MoveGroupInterface move_group(PLANNING_GROUP);

    moveit::planning_interface::PlanningSceneInterface planning_scene_interface;
    //Eigen::Vector3d b(0.001, 0.001, 0.001);
    sleep(2.0);

    std::vector<moveit_msgs::CollisionObject> collision_objects;
    collision_objects.resize(2);

    shapes::Mesh* m1 = shapes::createMeshFromResource("package://robot_description/meshes/RVIZ/shelf_stl.stl");
    ROS_INFO("shelf mesh loaded");

    sleep(2.0);

    shape_msgs::Mesh shelf_mesh;
    shapes::ShapeMsg shelf_mesh_msg;
    shapes::constructMsgFromShape(m1, shelf_mesh_msg);
    shelf_mesh = boost::get<shape_msgs::Mesh>(shelf_mesh_msg);
    collision_objects[0].id = "shelf";
    collision_objects[0].header.frame_id = "world";
    sleep(2.0);

    collision_objects[0].meshes.resize(1);
    collision_objects[0].mesh_poses.resize(1);
    collision_objects[0].meshes[0] = shelf_mesh;
    collision_objects[0].mesh_poses[0].position.x = 0.283853;
    collision_objects[0].mesh_poses[0].position.y = 0.730556;
    collision_objects[0].mesh_poses[0].position.z = -0.003741;
    collision_objects[0].mesh_poses[0].orientation.x = 0.999850;
    collision_objects[0].mesh_poses[0].orientation.y= 0.006747;
    collision_objects[0].mesh_poses[0].orientation.z= 0.000108;
    collision_objects[0].mesh_poses[0].orientation.w= 0.015920;

    collision_objects[0].meshes.push_back(shelf_mesh);
    collision_objects[0].mesh_poses.push_back(collision_objects[0].mesh_poses[0]);
    collision_objects[0].operation = collision_objects[0].ADD;

    // adding kaffee mesh

    shapes::Mesh* m2 = shapes::createMeshFromResource("package://robot_description/meshes/RVIZ/kaffee.stl");
    ROS_INFO("kaffee mesh loaded");

    sleep(2.0);

    shape_msgs::Mesh kaffee_mesh;
    shapes::ShapeMsg kaffee_mesh_msg;
    shapes::constructMsgFromShape(m2, kaffee_mesh_msg);
    kaffee_mesh = boost::get<shape_msgs::Mesh>(kaffee_mesh_msg);
    collision_objects[1].id = "kaffee";
    collision_objects[1].header.frame_id = "world";
    sleep(2.0);

    collision_objects[1].meshes.resize(1);
    collision_objects[1].mesh_poses.resize(1);
    collision_objects[1].meshes[0] = kaffee_mesh;
    collision_objects[1].mesh_poses[0].position.x = 0.325435;
    collision_objects[1].mesh_poses[0].position.y = 0.496533;
    collision_objects[1].mesh_poses[0].position.z = 0.422545;
    collision_objects[1].mesh_poses[0].orientation.x = -0.026790;
    collision_objects[1].mesh_poses[0].orientation.y= -0.001546;
    collision_objects[1].mesh_poses[0].orientation.z= 0.015858;
    collision_objects[1].mesh_poses[0].orientation.w= 0.999514;


    collision_objects[1].meshes.push_back(kaffee_mesh);
    collision_objects[1].mesh_poses.push_back(collision_objects[1].mesh_poses[0]);
    collision_objects[1].operation = collision_objects[1].ADD;    


    std::vector<moveit_msgs::CollisionObject> collision_vector;
    //collision_vector.resize(2);
    collision_vector.push_back(collision_objects[0]);  
    ROS_INFO("shelf added into the world");  

    collision_vector.push_back(collision_objects[1]);  
    ROS_INFO("kaffee added into the world"); 

    planning_scene_interface.applyCollisionObjects(collision_vector);
    sleep(5.0);
    ros::waitForShutdown();
    return 0;
}