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

Sending Rviz motion planning to Gazebo

asked 2020-05-09 12:25:02 -0500

matthewmarkey gravatar image

updated 2020-05-09 12:30:00 -0500

Kinetic Ubuntu 16.04

I have used the MSA to get all the appropriate files for Rviz motion planning simulation. It works perfectly with my custom 4DOF arm as well as will my custom move group python interface.

I now would like to take the next step and send these plans to gazebo. My first question is: is the demo_gazebo.launch that the MSA has written for me the correct launch file to preform motion planning in Gazebo? I have been attempting to figure out how the controllers work for several days now with no success.

After reading the material I have read, I am thoroughly confused on what controller <.yaml> file am supposed to utilize. My second question is, how am I supposed to use the appropriate launch files and .yaml files to get my model moving in gazebo? There are tutorials that use this type of file :

moveit_sim_hw_interface:
  joint_model_group: arm
  joint_model_group_pose: Home
# Settings for ros_control_boilerplate control loop
generic_hw_control_loop:
  loop_hz: 300
  cycle_time_error_threshold: 0.01
# Settings for ros_control hardware interface
hardware_interface:
  joints:
    - plat_joint
    - shoulder_joint
    - forearm_joint
    - wrist_joint
  sim_control_mode: 1  # 0: position, 1: velocity
# Publish all joint states
# Creates the /joint_states topic necessary in ROS
joint_state_controller:
  type: joint_state_controller/JointStateController
  publish_rate: 50
controller_list:
  []
arm:
  type: effort_controllers/JointPositionController
  joints:
    - plat_joint
    - shoulder_joint
    - forearm_joint
    - wrist_joint
  gains:
    plat_joint:
      p: 100
      d: 1
      i: 1
      i_clamp: 1
    shoulder_joint:
      p: 100
      d: 1
      i: 1
      i_clamp: 1
    forearm_joint:
      p: 100
      d: 1
      i: 1
      i_clamp: 1
    wrist_joint:
      p: 100
      d: 1
      i: 1
      i_clamp: 1

I have seen these files in this form:

controller_list:
  - name: arm
    action_ns: follow_joint_trajectory
    type: FollowJointTrajectory
    default: true
    joints:
      - plat_joint
      - shoulder_joint
      - forearm_joint
      - wrist_joint

as well as this way:

arm:
  # Publish all joint states -----------------------------------
    joint_state_controller:
      type: joint_state_controller/JointStateController
      publish_rate: 50
    # Position Controllers ---------------------------------------
    joint1_position_controller:
      type: effort_controllers/JointPositionController
      joint: plat_joint
      pid: {p: 0, i: 0.0, d: 0}
    joint2_position_controller:
      type: effort_controllers/JointPositionController
      joint: shoulder_joint
      pid: {p: 0, i: 0.0, d: 0}
    joint3_position_controller:
      type: effort_controllers/JointPositionController
      joint: forearm_joint
      pid: {p: 0, i: 0.0, d: 0}
    joint4_position_controller:
      type: effort_controllers/JointPositionController
      joint: wrist_joint
      pid: {p: 0, i: 0.0, d: 0}

When I run roslaunch arm_moveit_config demo_gazebo.launch:

-rviz simulation and motion planning spawns and works correctly

-gazebo spawn my robot model *not in the same position as the rviz model, the gazebo model looks collapsed as if affected by gravity with no controllers enabled and the model is slowly moving away from the origin.

-when I try to plan and execute the motion plan in rviz, the following following error appears in the window that roslaunch arm_moveit_config demo_gazebo.launch was run in:

[ INFO] [1589045034.162329986, 56.619000000]: SimpleSetup: Path simplification took 0.005122 seconds and changed from 3 to 2 states
[ INFO] [1589045034.165551729, 56.621000000]: Returned 0 controllers in list
[ERROR] [1589045034.165727411, 56.622000000]: Unable to identify any set of controllers that can actuate the specified joints: [ forearm_joint plat_joint shoulder_joint wrist_joint ]
[ERROR] [1589045034.166596511, 56.622000000]: Known controllers and their joints:

[ERROR] [1589045034.167526138, 56.622000000]: Apparently trajectory initialization failed
[ INFO] [1589045034.176038782, 56.632000000 ...
(more)
edit retag flag offensive close merge delete

Comments

Is Gazebo advertising a controller action? What is the output of rostopic list after running demo_gazebo.launch?

fvd gravatar image fvd  ( 2020-05-13 02:16:07 -0500 )edit

It was not advertising the controller action. The rostopic list was what I expected SANS the controllers. This was resolved however when question # 352048 was resolved.

matthewmarkey gravatar image matthewmarkey  ( 2020-05-13 04:43:33 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
0

answered 2020-05-13 04:47:01 -0500

matthewmarkey gravatar image

updated 2020-05-13 04:51:01 -0500

The issue was that I was not using the controller files correctly. Of the the three files that were posted above, I used the last two.

The following file is called controllers.yaml:

controller_list:
  - name: arm
    action_ns: follow_joint_trajectory
    type: FollowJointTrajectory
    default: true
    joints:
      - plat_joint
      - shoulder_joint
      - forearm_joint
      - wrist_joint

Is utilized when the .launch file is run while the controllers1.yaml file is run by ros_controllers.launch:

# Publish all joint states -----------------------------------
joint_state_controller:
  type: joint_state_controller/JointStateController
  publish_rate: 100
    # Position Controllers ---------------------------------------
# Control all joints
arm:
  type: effort_controllers/JointTrajectoryController
  joints:
    - plat_joint
    - shoulder_joint
    - forearm_joint
    - wrist_joint

  state_publish_rate: 100

  gains:
    plat_joint: {p: 100, i: 0.0, d: 0}
    shoulder_joint: {p: 100, i: 0.0, d: 0}
    forearm_joint: {p: 100, i: 0.0, d: 0}
    wrist_joint: {p: 100, i: 0.0, d: 0}

The names of the controllers above ('arm' and 'joint_state_controller') must be referenced in the file that launches this yaml file (ros_controllers.launch).

My git

edit flag offensive delete link more

Question Tools

2 followers

Stats

Asked: 2020-05-09 12:25:02 -0500

Seen: 594 times

Last updated: May 13 '20