gazebo::physics::get_world crashes node

asked 2016-08-17 21:53:47 -0500

jwatson_utah_edu gravatar image

ROS Indigo on Ubuntu 14.04 with Gazebo 7

I am trying to access the models in a Gazebo world via a node. In order to do this, I am just trying to get a reference to the world. Using the get_world function in the gazebo::physics namespace causes the node process to die. I try to catch the offending error below, but information from the error is not printed. The node just dies. The usage of this function in the docs seems straightforward. Why does this crash?

// ROS
#include <ros/ros.h>
#include <ros/package.h>
#include <std_msgs/Header.h>
#include <std_msgs/String.h>
#include <std_msgs/Char.h>
// Gazebo
#include <boost/bind.hpp>
#include <gazebo/gazebo.hh>
#include <gazebo/physics/physics.hh>
#include <gazebo/common/common.hh>
#include <stdio.h>
//#include "gazebo/GetWorldProperties.h" // DO I NEED THIS? , Error if included 

int main(int argc, char** argv){ // Accept args from the console

    ros::init(argc, argv, "attacher_node"); 

    ros::NodeHandle nh("attacher_handle"); // Start the node and give it a name

    ros::Publisher rNotifyPub = nh.advertise<std_msgs::String>( "/regrasp/notify" , 100 ); 

    std_msgs::String outMsg;

    try {
        // Get a reference to the world  
        gazebo::physics::WorldPtr worldRef = gazebo::physics::get_world("default"); 
    } catch (const std::exception& e) { // The error is never caught, process dies
        outMsg.data = e.what(); 
        rNotifyPub.publish(outMsg);
    }

    return 0; // Return OK
}

The following error information is printed when I run the launch file that calls the node:

[attacher_node-10] process has died [pid 28515, exit code -6, cmd /home/jwatson/regrasp_planning/devel/lib/grasp_anything/attacher_node __name:=attacher_node __log:=/home/jwatson/.ros/log/0e0eaf34-64e5-11e6-8d9b-0022191c2335/attacher_node-10.log].
log file: /home/jwatson/.ros/log/0e0eaf34-64e5-11e6-8d9b-0022191c2335/attacher_node-10*.log

The log file mentioned in the error message does not exist. When I try to open it in gedit it just creates the file.

edit retag flag offensive close merge delete