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

Problem with ros_control and gazebo

asked 2020-08-17 04:51:47 -0500

msaws gravatar image

updated 2020-08-19 06:36:09 -0500

I'm new to ros, I exported urdf from solidworks. when I add transmission to urdf and launch it gazebo is not opening it's giving me error as

[ INFO] [1597656176.792430594, 0.245000000]: Loading gazebo_ros_control plugin
[ INFO] [1597656176.793072386, 0.245000000]: Starting gazebo_ros_control plugin in namespace: /
[ INFO] [1597656176.794135347, 0.245000000]: gazebo_ros_control plugin is waiting for model URDF in parameter [robot_description] on the ROS param server.
Segmentation fault (core dumped)
[gazebo-1] process has died [pid 16223, exit code 139, cmd /home/xxxxx/catkin_ws/src/gazebo_ros_pkgs/gazebo_ros/scripts/gzserver -e ode worlds/empty.world __name:=gazebo __log:=/home/xxxx/.ros/log/5c2a3c2a-e069-11ea-a169-28d2447fbe91/gazebo-1.log].
log file: /home/xxxxx/.ros/log/5c2a3c2a-e069-11ea-a169-28d2447fbe91/gazebo-1*.log

but if I launch removing transmission tags it's launch perfectly.

I also tried with rrbot it gives me same error

edit: I've noticed it's because of this

<gazebo>
    <plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
        <robotNamespace>/</robotNamespace>
    </plugin>
</gazebo>

edit 2:

urdf:

<?xml version="1.0" encoding="utf-8"?>
<!-- This URDF was automatically created by SolidWorks to URDF Exporter! Originally created by Stephen Brawner (brawner@gmail.com) 
     Commit Version: 1.5.1-0-g916b5db  Build Version: 1.5.7152.31018
     For more information, please see http://wiki.ros.org/sw_urdf_exporter -->
<robot
  name="myrobot">
  <link
    name="base_link">
    <inertial>
      <origin
        xyz="-9.8696E-13 1.9623E-12 0.0045914"
        rpy="0 0 0" />
      <mass
        value="0.42609" />
      <inertia
        ixx="0.00066906"
        ixy="9.8933E-19"
        ixz="-1.1435E-20"
        iyy="0.00066906"
        iyz="-4.86E-20"
        izz="0.0013313" />
    </inertial>
    <visual>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <geometry>
        <mesh
          filename="package://myrobot/meshes/base_link.STL" />
      </geometry>
      <material
        name="">
        <color
          rgba="0.0549 0.8352941 0.05 1" />
      </material>
    </visual>
    <collision>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <geometry>
        <mesh
          filename="package://myrobot/meshes/base_link.STL" />
      </geometry>
    </collision>
  </link>
  <link
    name="axis_1">
    <inertial>
      <origin
        xyz="-1.9188529907279E-05 0.0408070112537518 -5.16123564547961E-05"
        rpy="0 0 0" />
      <mass
        value="1.0766304222928" />
      <inertia
        ixx="0.00448300046656785"
        ixy="-3.42116795702848E-07"
        ixz="-4.62222489752297E-07"
        iyy="0.00764833990366456"
        iyz="-9.51387517754669E-07"
        izz="0.00478779956731877" />
    </inertial>
    <visual>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <geometry>
        <mesh
          filename="package://myrobot/meshes/axis_1.STL" />
      </geometry>
      <material
        name="">
        <color
          rgba="0.96078 0.9490196 0.196078 1" />
      </material>
    </visual>
    <collision>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <geometry>
        <mesh
          filename="package://myrobot/meshes/axis_1.STL" />
      </geometry>
    </collision>
  </link>
  <joint
    name="CS1_JY"
    type="revolute">
    <origin
      xyz="0 0 -0.007418"
      rpy="1.5708 0 0" />
    <parent
      link="base_link" />
    <child
      link="axis_1" />
    <axis
      xyz="0 1 0" />
    <limit
      lower="-3.1416"
      upper="3.1416"
      effort="16.65"
      velocity="1.0472" />
  </joint>
  <link
    name="axis_2">
    <inertial>
      <origin
        xyz="0.000584059554378004 0.0287533737382525 0.00295671723448659"
        rpy="0 0 0" /> ...
(more)
edit retag flag offensive close merge delete

Comments

@msaws You say you have tried this and this tutorial which expain you how to deal with URDF, ROS_control and Gazebo? It is strange that this does not work... Are you able to post your description and configuration files? With the information you gave it seems that the Controllers are not properly loaded in ROS_control, maybe you gave a wrong joint name or your configuration file is not properly written. Besides I recommend you to work on a proper namespace and not over the global /.

Weasfas gravatar image Weasfas  ( 2020-08-18 05:05:54 -0500 )edit

@Weasfas I checked the joint names, I don't think the problem is with controllers not loading because I even tried to with roslaunch rrbot_gazebo rrbot_world.launch it gives me same error. I think the problem is with gazebo_ros_control plugin I'm not sure I couldn't figure out the problem

msaws gravatar image msaws  ( 2020-08-18 05:21:39 -0500 )edit

I do not think it is a problem of gazebo_ros_control, you are getting a segmentation fault expection. If the problem was in ROS control it should warn yourself of the controllers not loading, and it does not even reach that part. Ensure you have all dependencies installed and your URDF and world are correct. In the past I have experienced the same issue when I load a wrong URDF or the .world file was bad formatted.

Furthermore the plugin needs several parameters like:

<gazebo>
    <plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
        <robotNamespace>/your_namespace</robotNamespace>
        <robotParam>your_robot_description</robotParam>
        <controlPeriod>0.001</controlPeriod>
        <robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType>
        <legacyModeNS>true</legacyModeNS>
    </plugin>
</gazebo>
Weasfas gravatar image Weasfas  ( 2020-08-18 11:49:27 -0500 )edit

I changed my plugin to

<gazebo>
    <plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
        <robotNamespace>/myrobot</robotNamespace>
        <robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType>
        <robotParam>/myrobot/robot_description</robotParam>
        <legacyModeNS>true</legacyModeNS>
    </plugin>
</gazebo>

it gave me

[ INFO] [1597769945.328490084]: Starting gazebo_ros_control plugin in namespace: /myrobot
[ INFO] [1597769945.329537727]: gazebo_ros_control plugin is waiting for model URDF in parameter [/myrobot/robot_description] on the ROS param server.
[urdf_spawner-4] process has finished cleanly

I hope this correct but when I launch my controller

[INFO] [1597769968.108590]: Controller Spawner: Waiting for service controller_manager/load_controller
[WARN] [1597769998.349820]: Controller Spawner couldn't find the expected controller_manager ROS interface.
[myrobot/controller_spawner-1] process has finishe
msaws gravatar image msaws  ( 2020-08-18 12:06:07 -0500 )edit

And what all dependencies should I install?

msaws gravatar image msaws  ( 2020-08-19 02:40:48 -0500 )edit

You need to load your robot_description in the proper namespace and I was refering to the dependencies from gazebo_ros_control, gazebo_ros_plugins, and each dependency package regarding the controllers you are using: joint_position, joint_effort etc. It will be easier if you post the launch files or something to debug what is happening.

Weasfas gravatar image Weasfas  ( 2020-08-19 06:02:23 -0500 )edit

@Weasfas I've updated the question and added my urdf and controller, I don't know why but I couldn't add more so I'm adding my launch files here in comments

msaws gravatar image msaws  ( 2020-08-19 06:42:34 -0500 )edit

controller launch file:

<launch>
  <rosparam file="$(find myrobot)/config/arm_controller.yaml" command="load"/>

  <node name="controller_spawner" pkg="controller_manager" type="spawner" respawn="false"
    output="screen" ns="/myrobot" args="joint_state_controller
                      joint1_position_controller
                      joint2_position_controller
                                          joint3_position_controller
                      joint4_position_controller
                                          joint5_position_controller
                      joint6_position_controller
                                          joint7_position_controller
                      joint8_position_controller"/>

  <node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher"
    respawn="false" output="screen">
    <remap from="/joint_states" to="/myrobot/joint_states" />
  </node>

</launch>
msaws gravatar image msaws  ( 2020-08-19 06:44:02 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
1

answered 2020-08-24 10:08:56 -0500

Weasfas gravatar image

I will post this as an answer but I do not know if it solve your problem. At least in my machine I was able to load all controllers and control the platform. So here we go:

I used you same URDF loading it as a xacro file (with the world fixed joint).

Then, I used these launch files:

For the robot_description:

<?xml version="1.0"?>

<launch>

  <!-- Do not launch Gazebo simulator and use Joint State publisher to debug joints -->
  <arg name="sim" default="false"/>
  <arg name="output" default="log"/>

  <!-- Load the URDF into the ROS Parameter Server -->
  <param name="robot_description"
    command="$(find xacro)/xacro --inorder '$(find myrobot_description)/urdf/myrobot.xacro'" />

  <!-- State joints publisher for debug -->
  <node unless="$(arg sim)" name="joint_state_publisher" pkg="joint_state_publisher"
    type="joint_state_publisher" output="$(arg output)" />

  <!-- Combine joint values -->
  <node name="robot_state_publisher" pkg="robot_state_publisher"
    type="robot_state_publisher" output="$(arg output)" />

  <!-- Launch Rviz for visualization -->
  <node name="rviz" pkg="rviz" type="rviz" />

</launch>

For the robot control:

<?xml version="1.0"?>

<launch>

  <!-- Coordinates to spawn model -->
  <arg name="x" default="0.0"/>
  <arg name="y" default="0.0"/>
  <arg name="z" default="0.01"/>
  <arg name="roll" default="0.0"/>
  <arg name="pitch" default="0.0"/>
  <arg name="yaw" default="0.0"/>

  <arg name="output" default="log"/>

  <!-- Load joint controller configurations from YAML file to parameter server -->
  <rosparam file="$(find myrobot_control)/config/myrobot_control.yaml" command="load"/>

  <!-- Start controllers -->
  <node name="controller_spawner" pkg="controller_manager" type="spawner" respawn="false"
    output="$(arg output)" args="
    joint_state_controller
    joint1_position_controller
    joint2_position_controller
    joint3_position_controller
    joint4_position_controller
    joint5_position_controller
    joint6_position_controller
    joint7_position_controller
    joint8_position_controller" />

  <!-- Run a python script to the send a service call to gazebo_ros to spawn a URDF robot -->
  <node name="urdf_spawner" pkg="gazebo_ros" type="spawn_model" respawn="false" output="$(arg output)"
    args="-urdf -model myrobot -param robot_description -x $(arg x) -y $(arg y) -z $(arg z) -R $(arg roll) -P $(arg pitch) -Y $(arg yaw)"/>

</launch>

And the control config file:

# Publish all joint states -----------------------------------
joint_state_controller:
  type: joint_state_controller/JointStateController
  publish_rate: 50  

# Position Controllers ---------------------------------------
joint1_position_controller:
  type: effort_controllers/JointEffortController
  joint: CS1_JY
  pid: {p: 100.0, i: 0.0, d: 0.0}
joint2_position_controller:
  type: effort_controllers/JointEffortController
  joint: CS2_JX
  pid: {p: 100.0, i: 0.0, d: 0.0}
joint3_position_controller:
  type: effort_controllers/JointEffortController
  joint: CS3_JX
  pid: {p: 100.0, i: 0.0, d: 0.0}
joint4_position_controller:
  type: effort_controllers/JointEffortController
  joint: CS4_JZ
  pid: {p: 100.0, i: 0.0, d: 0.0}
joint5_position_controller:
  type: effort_controllers/JointEffortController
  joint: CS5_JX
  pid: {p: 100.0, i: 0.0, d: 0.0}
joint6_position_controller:
  type: effort_controllers/JointEffortController
  joint: CS6_JZ
  pid: {p: 100.0, i: 0.0, d: 0.0}
joint7_position_controller:
  type: effort_controllers/JointEffortController
  joint: CSEF_RXminus
  pid: {p: 100.0, i: 0.0, d: 0.0}
joint8_position_controller:
  type: effort_controllers/JointEffortController
  joint: CSEF_LXplus
  pid: {p: 100.0, i: 0.0, d: 0.0}

And finally to spawn the robot and launch it in ... (more)

edit flag offensive delete link more

Comments

Thank You so much for the help.

I don't understand what's the problem with my machine, I launch the exact same files as you have mentioned still got the the same segfault and Controller Spawner couldn't find the expected controller_manager ROS interface.

msaws gravatar image msaws  ( 2020-08-24 14:22:33 -0500 )edit
1

@msaws, Well in that case I do not have more ideas, maybe tried your package in another environment, you can try it in a virtual machine.

Weasfas gravatar image Weasfas  ( 2020-08-25 04:08:12 -0500 )edit

@Weasfas I tried in another machine and it was working perfectly fine, I think there's a problem with my machine some kind of installation problem I think. Should I uninstall and reinstall ROS and gazebo from the start?

msaws gravatar image msaws  ( 2020-08-26 03:37:59 -0500 )edit
1

@msaws: there is a good chance you have a problem with partial updates. It's not uncommon to receive SEGFAULTs in that case.

Make sure to have updated all ROS packages for Melodic.

And to be clear: I'm not suggesting to build anything from sources, but to make sure you have all updates installed via apt.

gvdhoorn gravatar image gvdhoorn  ( 2020-08-26 03:51:55 -0500 )edit

How do I update all the packages?

I mean which packages do I need to update

msaws gravatar image msaws  ( 2020-08-26 03:59:21 -0500 )edit

As you would normally update your Ubuntu 18.04 packages.

I don't know what method you normally use.

Could be apt update && apt dist-upgrade, could be Synaptic, Ubuntu Software, etc.

Just make sure everything is up-to-date, and make sure to completely rebuild any ROS workspaces you have as well (so rm -rf devel/ build/ install/ logs/ and then build with Catkin).

gvdhoorn gravatar image gvdhoorn  ( 2020-08-26 04:06:37 -0500 )edit

Question Tools

3 followers

Stats

Asked: 2020-08-17 04:29:56 -0500

Seen: 2,174 times

Last updated: Aug 24 '20