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

moveit_msgs::CollisionObjects has no member named meshs/ meshes_pose etc

asked 2019-03-02 06:59:58 -0500

mvish7 gravatar image

Hello,

I'm trying to add a mesh into rviz as a collision object on ros_kinetic. Below is the code i'm using:

// ROS
#include <ros/ros.h>

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

// TF2
#include <tf2_geometry_msgs/tf2_geometry_msgs.h>



void addCollisionObjects(moveit::planning_interface::PlanningSceneInterface& planning_scene_interface)
{

  // Creating Environment

std::vector<moveit_msgs::CollisionObject> collision_object;
collision_object.resize(1);
Eigen::Vector3d b(0.001, 0.001, 0.001);

collision_object[0].id = "shelf";
shapes::Mesh* m = shapes::createMeshFromResource("package://robot_description/meshes/RVIZ/shelf_dae.dae",b);


shape_msgs::Mesh mesh;
shapes::ShapeMsg mesh_msg;
shapes::constructMsgFromShape(m, mesh_msg);
mesh = boost::get<shape_msgs::Mesh>(mesh_msg);

collision_object.meshes.resize(1);
collision_object.mesh_poses.resize(1);
collision_object.meshes[0] = mesh;
collision_object.header.frame_id = "panda_link0";
collision_object.mesh_poses[0].position.x = 0.283853;
collision_object.mesh_poses[0].position.y = 0.730556;
collision_object.mesh_poses[0].position.z = -0.003741;
collision_object.mesh_poses[0].orientation.x = 0.999850;
collision_object.mesh_poses[0].orientation.y= 0.006747;
collision_object.mesh_poses[0].orientation.z= 0.000108;
collision_object.mesh_poses[0].orientation.w= 0.015920;

collision_object.meshes.push_back(mesh);
collision_object.mesh_poses.push_back(collision_object.mesh_poses[0]);
collision_object.operation = collision_object[0].ADD;
std::vector<moveit_msgs::CollisionObject> collision_vector;
collision_vector.push_back(collision_object);

planning_scene_interface.applyCollisionObjects(collision_vector);
planning_scene_interface.(collision_object[0].id);

}

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

  ros::WallDuration(1.0).sleep();
  moveit::planning_interface::PlanningSceneInterface planning_scene_interface;
  moveit::planning_interface::MoveGroupInterface group("panda_arm");
  group.setPlanningTime(45.0);

  addCollisionObjects(planning_scene_interface);

  // Wait a bit for ROS things to initialize
  ros::WallDuration(1.0).sleep();

  //pick(group);
}

When i run catkin_make i get lot of errors which can be seen below

[ 50%] Built target fetch_model_poses
[ 75%] Building CXX object robot_moveit_config/CMakeFiles/moveit_interface.dir/src/moveit_interface.cpp.o
/home/mvish7/ws_panda_gazebo_moveit/src/robot_moveit_config/src/moveit_interface.cpp: In function ‘void addCollisionObjects(moveit::planning_interface::PlanningSceneInterface&)’:
/home/mvish7/ws_panda_gazebo_moveit/src/robot_moveit_config/src/moveit_interface.cpp:35:18: error: ‘class std::vector<moveit_msgs::CollisionObject_<std::allocator<void> > >’ has no member named ‘meshes’
 collision_object.meshes.resize(1);
                  ^
/home/mvish7/ws_panda_gazebo_moveit/src/robot_moveit_config/src/moveit_interface.cpp:36:18: error: ‘class std::vector<moveit_msgs::CollisionObject_<std::allocator<void> > >’ has no member named ‘mesh_poses’
 collision_object.mesh_poses.resize(1);
                  ^
/home/mvish7/ws_panda_gazebo_moveit/src/robot_moveit_config/src/moveit_interface.cpp:37:18: error: ‘class std::vector<moveit_msgs::CollisionObject_<std::allocator<void> > >’ has no member named ‘meshes’
 collision_object.meshes[0] = mesh;
                  ^
/home/mvish7/ws_panda_gazebo_moveit/src/robot_moveit_config/src/moveit_interface.cpp:38:18: error: ‘class std::vector<moveit_msgs::CollisionObject_<std::allocator<void> > >’ has no member named ‘header’
 collision_object.header.frame_id = "panda_link0";
                  ^
/home/mvish7/ws_panda_gazebo_moveit/src/robot_moveit_config/src/moveit_interface.cpp:39:18: error: ‘class std::vector<moveit_msgs::CollisionObject_<std::allocator<void> > >’ has no member named ‘mesh_poses’
 collision_object.mesh_poses[0].position.x = 0.283853;
                  ^
/home/mvish7/ws_panda_gazebo_moveit/src/robot_moveit_config/src/moveit_interface.cpp:40:18: error: ‘class std::vector<moveit_msgs::CollisionObject_<std::allocator<void> > >’ has no member named ‘mesh_poses’
 collision_object.mesh_poses[0].position.y = 0.730556;
                  ^
/home/mvish7/ws_panda_gazebo_moveit/src/robot_moveit_config/src/moveit_interface.cpp:41:18: error: ‘class std::vector ...
(more)
edit retag flag offensive close merge delete

2 Answers

Sort by » oldest newest most voted
1

answered 2019-03-04 02:17:08 -0500

mvish7 gravatar image

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 ...
(more)
edit flag offensive delete link more
1

answered 2019-03-04 02:04:53 -0500

aPonza gravatar image

Start from the first error:

/home/mvish7/ws_panda_gazebo_moveit/src/robot_moveit_config/src/moveit_interface.cpp: In function ‘void addCollisionObjects(moveit::planning_interface::PlanningSceneInterface&)’:
/home/mvish7/ws_panda_gazebo_moveit/src/robot_moveit_config/src/moveit_interface.cpp:35:18: error: ‘class std::vector<moveit_msgs::CollisionObject_<std::allocator<void> > >’ has no member named ‘meshes’
 collision_object.meshes.resize(1);
                  ^

Read the error message carefully: class std::vector<moveit_msgs::CollisionObject_<std::allocator<void> > >’ has no member named ‘meshes’.

Does it make sense? Why is the compiler complaining?

You're using a container, std::vector, that contains multiple moveit_msgs::CollisionObject type objects. This last type does have a member named meshes, but std::vector doesn't.

The solution: access one of the members, changing collision_object.meshes.resize(1); into collision_object[0].meshes.resize(1); or collision_object.at(0).meshes.resize(1); for example.

This is a C++ problem, not a ROS problem though.

edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2019-03-02 06:59:58 -0500

Seen: 1,133 times

Last updated: Mar 04 '19