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

spawned robot in Gazebo is moving by itself (Moveit!)

asked 2019-11-14 07:06:33 -0500

marko1990 gravatar image

updated 2019-11-22 15:21:49 -0500

jayess gravatar image

Hello everyone,

This is my first question, so please have some understanding if I haven't posted it like it was meant to be posted. I am running Ubuntu 18.04.2 with ROS_Melodic and Gazebo 9, I have also installed Moveit! package like it was explained in the moveit tutorial, after that I have made catkin package and in the src folder I have git cloned the fanuc moveit! package(Kinetic distro) and all dependent packages for a fanuc in this case. I have sourced and built the workspace (using catkin build). I have chosen the fanuc_m16ib20 robot (it was random choice) and I have made the moveit package like in instructions for the moveit_setup_assistant. At the end of the package generation in setup_assistant I was offered the URDF file for the made configuration, I have copied it and saved it under mypackage/urdf path. After this I have added the Gazebo plugin to the URDF file

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

Also I wanted to fix(anchor) the robot to the world and I added this to the beginning of the URDF file:

  <link name="world"></link>
  <joint name="fixed" type="fixed">
     <parent link="world"/>
     <child link="base_link"/>
  </joint>

Next thing I have done is, added the namespace fanuc_m16ib20 to the controllers, controller spawner and controller manager. I have modified the demo_gazebo.launch file to do this and controller.yaml files accordingly.

After this changes all it was left to do is to try and run the demo_gazebo.launchfile, but after running it Gazebo and Rviz are started but the robot in the Gazebo is moving by itself. Since it is connected to the RViz I can see the same behaviour in the RViz, with the exception, in RViz there robot joints stay connected. When I run rostopic list or rosservice list I can see topics and controller manager under the same namespace.

topics:

> /fanuc_m16ib20/fanuc_arm_controller/command
/fanuc_m16ib20/fanuc_arm_controller/follow_joint_trajectory/cancel
/fanuc_m16ib20/fanuc_arm_controller/follow_joint_trajectory/feedback
/fanuc_m16ib20/fanuc_arm_controller/follow_joint_trajectory/goal
/fanuc_m16ib20/fanuc_arm_controller/follow_joint_trajectory/result
/fanuc_m16ib20/fanuc_arm_controller/follow_joint_trajectory/status
/fanuc_m16ib20/fanuc_arm_controller/state
/fanuc_m16ib20/joint_states

services:

/fanuc_m16ib20/controller_manager/list_controller_types
/fanuc_m16ib20/controller_manager/list_controllers
/fanuc_m16ib20/controller_manager/load_controller
/fanuc_m16ib20/controller_manager/reload_controller_libraries
/fanuc_m16ib20/controller_manager/switch_controller
/fanuc_m16ib20/controller_manager/unload_controller

I have these errors and a few warnings:

[ERROR] [1573735342.035351047]: name, joints, action_ns, and type must be specifed for each controller

[ERROR] [1573735343.777676683, 0.001000000]: No p gain specified for pid.  Namespace: /fanuc_m16ib20/gazebo_ros_control/pid_gains/joint_1
[ERROR] [1573735343.779464187, 0.001000000]: No p gain specified for pid.  Namespace: /fanuc_m16ib20/gazebo_ros_control/pid_gains/joint_2
[ERROR] [1573735343.781116227, 0.001000000]: No p gain specified for pid.  Namespace: /fanuc_m16ib20/gazebo_ros_control/pid_gains/joint_3
[ERROR] [1573735343.783848394, 0.001000000]: No p gain specified for pid.  Namespace: /fanuc_m16ib20/gazebo_ros_control/pid_gains/joint_4
[ERROR] [1573735343.785975603, 0.001000000]: No p gain specified for pid.  Namespace: /fanuc_m16ib20/gazebo_ros_control/pid_gains/joint_5
[ERROR] [1573735343.797053511, 0.001000000]: No p gain specified for pid.  Namespace: /fanuc_m16ib20/gazebo_ros_control/pid_gains/joint_6

After solving the ... (more)

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
0

answered 2019-11-21 14:50:28 -0500

marko1990 gravatar image

Ok after hours of trying to understand what went wrong I have finally figured it out. The problem was not in the /controller_list parameter, it was because the parameter move_group/controller_list was missing and since I am using namespaces I have a controller_list.yamlas a separate .yaml file and I have loaded it in the ros_controllers.launch right after ros_controllers.yaml.

I thought that was all, but controllers have to be loaded under moveit also it is not enough just to load them under ros_control like I explained before, by this I mean I should have loaded controller_list.yaml file under the move_group namespace in a move_group.launch also. This means and I am assuming you made yourrobot_pkg with the moveit_assistant and you are using an urdf file created by moveit_assistant (after that you have added your namespaces if neccesarry): in yourrobot_moveit_pkg start demo_gazebo.launch which should have this structure (mostly made by moveit):

 different arguments declarations
        .
        .
   gazebo.launch     
      -> robot_description(urdf) to param server
      -> spawns robot_description param in gazebo
      -> ros_controllers.launch //ros_controllers and the controller_list to the param server
   node joint_state_publisher
   node robot_state_publisher
   move_group.launch
      -> different arguments declarations
                                 .
                                 .
      -> trajectory_execution.launch.xml // load launch file under the `move_group` namespace
                -> different arguments declarations
                                          .
                                          .
                         $(arg moveit_controller_manager)_moveit_controller_manager.launch.xml
                               //loads moveit_simple_controller_manager on the parameter server 
                               // load controllers on the parameter server
                                  ros_controllers.yaml
                                  controlller_list.yaml

Basically you need to think about your namespaces and I think the first loading of the controller_list.yaml in the ros_control could be taken out. Because it is important that the controller_list parameter is loaded under the move_group namespace.

edit flag offensive delete link more

Question Tools

2 followers

Stats

Asked: 2019-11-14 07:06:33 -0500

Seen: 1,691 times

Last updated: Nov 21 '19