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

node crashes with "ros does not seem to be running"

asked 2020-04-25 17:31:13 -0500

DaxJadz gravatar image

updated 2020-04-26 01:22:10 -0500

gvdhoorn gravatar image

I have create a node, but each time I try and start it using a .launch file that just launches the node, I get:

process[simon_says_main_M_node-1]: started with pid [11354]
terminate called after throwing an instance of 'std::runtime_error'
  what():  ROS does not seem to be running
[simon_says_main_M_node-1] process has died [pid 11354, exit code -6, cmd /home/elsa/bax_ws/devel/lib/simon_says_main/simon_says_main_M_node __name:=simon_says_main_M_node __log:=/home/elsa/.ros/log/bed59e4c-873f-11ea-bd6a-305a3a7c519b/simon_says_main_M_node-1.log].
log file: /home/elsa/.ros/log/bed59e4c-873f-11ea-bd6a-305a3a7c519b/simon_says_main_M_node-1*.log

The log file does not exist. Using rosrun to launch the node gives the same result. The node does run on another computer, and both have the same setup of packages and so on as far as I can tell.

using rosrun results in:

[baxter - http://localhost:11311] elsa@Inanna:~/bax_ws$ rosrun simon_says_main simon_says_main_M_node 
terminate called after throwing an instance of 'std::runtime_error'
  what():  ROS does not seem to be running
Aborted (core dumped)

The code for the node is:

#include <pluginlib/class_loader.h>
#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/DisplayRobotState.h>
#include <moveit_msgs/DisplayTrajectory.h>

#include <moveit_msgs/AttachedCollisionObject.h>
#include <moveit_msgs/CollisionObject.h>

#include <moveit_visual_tools/moveit_visual_tools.h>


#include <boost/scoped_ptr.hpp>


/*
 To Run:
 1) start baxter
 2) rosrun baxter_tools enable_robot.py -e
 3) rosrun baxter_interface joint_trajectory_action_server.py
 4) roslaunch baxter_moveit_config demo_baxter.launch right_electric_gripper:=true left_electric_gripper:=true
 5) rosrun simon_says_main simon_says_main_M_node

 #get the current end effector coordinates
$ rostopic echo /robot/limb/right/endpoint_state 
*/

static const std::string PLANNING_GROUP_L = "left_arm";
static const std::string PLANNING_GROUP_R = "right_arm";

moveit::planning_interface::MoveGroupInterface move_group_L(PLANNING_GROUP_L);
moveit::planning_interface::MoveGroupInterface move_group_R(PLANNING_GROUP_R);

void dab()
  {
    //plan right arm
    geometry_msgs::Pose rp;
    rp.orientation.w = 0.67;
    rp.position.x = 0.357;
    rp.position.y = -0.08;
    rp.position.z = 0.39;
    move_group_R.setPoseTarget(rp);

    //plan left arm
    geometry_msgs::Pose lp;
    lp.orientation.w = 0.73;
    lp.position.x = 0.26;
    lp.position.y = 1.18;
    lp.position.z = 1.08;
    move_group_L.setPoseTarget(lp);

    moveit::planning_interface::MoveGroupInterface::Plan my_plan_R;
    moveit::planning_interface::MoveGroupInterface::Plan my_plan_L;

    bool success_R = (move_group_R.plan(my_plan_R) == moveit::planning_interface::MoveItErrorCode::SUCCESS);
    bool success_L = (move_group_L.plan(my_plan_L) == moveit::planning_interface::MoveItErrorCode::SUCCESS);

    ROS_INFO_NAMED("tutorial", "Visualizing dab - right arm (pose goal) %s", success_R ? "" : "FAILED");
    ROS_INFO_NAMED("tutorial", "Visualizing dab - left arm (pose goal) %s", success_L ? "" : "FAILED");

    move_group_L.move();
    move_group_R.move();

  /*
  DAB - RIGHT
    pose: 
      position: 
        x: 0.357449700371
        y: -0.0845383821871
        z: 0.398438102254
      orientation: 
        x: -0.347113539773
        y: -0.354022093046
        z: -0.548629443089
        w: 0.673191118715
  DAB - LEFT
      frame_id: ''
    pose: 
      position: 
        x: 0.265252415343
        y: 1.18807756952
        z: 1.08236724242
      orientation: 
        x: -0.260426879784
        y: 0.376068085189
        z: 0.494750557147
        w: 0.738899534301
  */
  }

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

  printf("Hi!\n");

  moveit::planning_interface::PlanningSceneInterface planning_scene_interface;

  //iffy, don't need
  //move_group.getCurrentState()->getJointModelGroup(PLANNING_GROUP);

  // Visualization: The package MoveItVisualTools provides many capabilities for visualizing objects, robots, and trajectories in RViz as well as debugging tools such as step-by-step introspection of a script.
  namespace rvt = rviz_visual_tools ...
(more)
edit retag flag offensive close merge delete

Comments

I'm not entirely sure, but you appear to be initialising two moveit::planning_interface::MoveGroupInterface instances as global variables (move_group_L and move_group_R), which could be causing the error you get. MoveGroupInterface as part of its initialisation requires certain ROS functionality, and if you haven't initialised ROS before creating those MoveGroupInterfaces, they will likely complain.

gvdhoorn gravatar image gvdhoorn  ( 2020-04-26 01:24:13 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
0

answered 2020-05-02 15:27:06 -0500

DaxJadz gravatar image

The comment by Gvdhoom and this question that has a different error message but the same underlying problem cleared it up for me.
The Cause: Some of my global variables were objects that created NodeHandle objects within their internal implementation. Since they are global variables, they were constructed before main (and ros::init()) were run.

The Solution: I changed

static const std::string PLANNING_GROUP_L = "left_arm";

moveit::planning_interface::MoveGroupInterface move_group_L(PLANNING_GROUP_L);

To

static const std::string PLANNING_GROUP_L = "left_arm";

moveit::planning_interface::MoveGroupInterface *move_group_L;

void setup()
{
left_arm = new moveit::planning_interface::MoveGroupInterface(PLANNING_GROUP_L);
}

And replaced any left_arm.<something> with left_arm-><something>. I also found that making a global tf2_ros::TransformListener and tf2_ros::TransformBroadcaster cause the same issue, and are fixable with the same solution above.

edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2020-04-25 17:24:18 -0500

Seen: 831 times

Last updated: May 02 '20