How to import stl-file in tesseract RVIZ as a collision object

asked 2019-03-18 15:16:23 -0500

DieterWuytens gravatar image

updated 2019-03-18 16:53:13 -0500

Currently working with RVIZ and Trajopt planning (with ros tesseract) Previously i worked with ompl and added my stl-file (mesh, which was a wall) as a collision object in the RVIZ motionplanning display. Which was done by the following code:

#include "ros/ros.h"
#include "moveit/move_group_interface/move_group_interface.h"
#include "geometric_shapes/shapes.h"
#include "geometric_shapes/mesh_operations.h"
#include "geometric_shapes/shape_operations.h"
#include "moveit/planning_scene_interface/planning_scene_interface.h"

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

    moveit::planning_interface::PlanningSceneInterface planning_scene_interface;
    sleep(2.0);

    moveit_msgs::CollisionObject wall;
    shapes::Mesh* m = shapes::createMeshFromResource("package://robot_config/meshes/wall.stl");
    ROS_INFO("Wall imported!");  
    shape_msgs::Mesh wall_mesh;
    shapes::ShapeMsg wall_mesh_msg;
    shapes::constructMsgFromShape(m,wall_mesh_msg);
    wall_mesh = boost::get<shape_msgs::Mesh>(wall_mesh_msg);
    wall.meshes.resize(1);
    wall.meshes[0] = wall_mesh;
    wall.mesh_poses.resize(1);

    // ORIGINAL VALUES X = 0.0; Y = 1.0; Z = 0.0
    wall.mesh_poses[0].position.x = -0.5;
    wall.mesh_poses[0].position.y = 1.0;
    wall.mesh_poses[0].position.z = -1.0;
    wall.mesh_poses[0].orientation.w= 1.0;
    wall.mesh_poses[0].orientation.x= 0.0;
    wall.mesh_poses[0].orientation.y= 0.0;
    wall.mesh_poses[0].orientation.z= 0.0;

    wall.meshes.push_back(wall_mesh);
    wall.mesh_poses.push_back(wall.mesh_poses[0]);
    wall.operation = wall.ADD;

    std::vector<moveit_msgs::CollisionObject> collision_objects;  
    collision_objects.push_back(wall);  

    ROS_INFO("Wall created");  
    planning_scene_interface.addCollisionObjects(collision_objects);
}

How can i change this code to be used with tesseract and trajopt and add the stl as a collision object in RVIZ? I'm using kinetic.

edit retag flag offensive close merge delete