ros-industrial / universal_robot

ROS-Industrial Universal Robots support (https://wiki.ros.org/universal_robot)
1.1k stars 1.04k forks source link

[melodic] UR5 Moveit model not showing correctly #374

Closed Pro closed 6 years ago

Pro commented 6 years ago

I am on a newly installed Ubuntu 18.04 with ROS Melodic.

I installed all the ROS packages with apt and then cloned the universal_robot repo into my workspace.

Then I run:

roslaunch ur_gazebo ur5.launch   
roslaunch ur5_moveit_config ur5_moveit_planning_execution.launch sim:=true
roslaunch ur5_moveit_config moveit_rviz.launch config:=true

which opens the following windows:

image

image

As you can see in RViz the robot looks somehow broken. If I try to plan a path, it always fails since the robot is already colliding.

If I check the position property of the links, they are all set to 0,0,0...

Do you have any clues how to fix this?

Thanks!

gavanderhoorn commented 6 years ago

This could be a Gazebo 9 incompatibility issue.

Could you please provide us with the version of Gazebo you have running and a single message from the /joint_states topic.

Pro commented 6 years ago

Here are the versions I have installed:

ros-melodic-gazebo-ros-control/bionic,now 2.8.4-0bionic.20180710.223050 amd64 
gazebo9/bionic,now 9.0.0+dfsg5-3ubuntu1 amd64 [installed,automatic]

And the output of joint_states is:

---
header: 
  seq: 2638
  stamp: 
    secs: 53
    nsecs: 413000000
  frame_id: ''
name: [elbow_joint, shoulder_lift_joint, shoulder_pan_joint, wrist_1_joint, wrist_2_joint,
  wrist_3_joint]
position: [8.404066400302668e-05, 0.013313130523400218, 0.00048356653853609544, 0.0004878671203663032, -5.116296311058477e-06, 3.773704196063932e-05]
velocity: [0.00019241551370976356, 0.04266308535101533, -0.0001239670664260386, 0.0014172778802119534, -7.408810395117624e-06, 0.00011813872303687023]
effort: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0]

IMHO the joint states message should be fine?

Here are the outputs of the launch commands:

roslaunch ur_gazebo ur5.launch

Checking log directory for disk usage. This may take awhile.
Press Ctrl-C to interrupt
Done checking log file disk usage. Usage is <1GB.

xacro: in-order processing became default in ROS Melodic. You can drop the option.
started roslaunch server http://pc1-n-094:32775/

SUMMARY
========

PARAMETERS
 * /arm_controller/action_monitor_rate: 10
 * /arm_controller/constraints/elbow_joint/goal: 0.1
 * /arm_controller/constraints/elbow_joint/trajectory: 0.1
 * /arm_controller/constraints/goal_time: 0.6
 * /arm_controller/constraints/shoulder_lift_joint/goal: 0.1
 * /arm_controller/constraints/shoulder_lift_joint/trajectory: 0.1
 * /arm_controller/constraints/shoulder_pan_joint/goal: 0.1
 * /arm_controller/constraints/shoulder_pan_joint/trajectory: 0.1
 * /arm_controller/constraints/stopped_velocity_tolerance: 0.05
 * /arm_controller/constraints/wrist_1_joint/goal: 0.1
 * /arm_controller/constraints/wrist_1_joint/trajectory: 0.1
 * /arm_controller/constraints/wrist_2_joint/goal: 0.1
 * /arm_controller/constraints/wrist_2_joint/trajectory: 0.1
 * /arm_controller/constraints/wrist_3_joint/goal: 0.1
 * /arm_controller/constraints/wrist_3_joint/trajectory: 0.1
 * /arm_controller/joints: ['shoulder_pan_jo...
 * /arm_controller/state_publish_rate: 25
 * /arm_controller/stop_trajectory_duration: 0.5
 * /arm_controller/type: position_controll...
 * /gazebo/enable_ros_network: True
 * /joint_state_controller/publish_rate: 50
 * /joint_state_controller/type: joint_state_contr...
 * /robot_description: <?xml version="1....
 * /robot_state_publisher/publish_frequency: 50.0
 * /robot_state_publisher/tf_prefix: 
 * /rosdistro: melodic
 * /rosversion: 1.14.2
 * /use_sim_time: True

NODES
  /
    arm_controller_spawner (controller_manager/controller_manager)
    fake_joint_calibration (rostopic/rostopic)
    gazebo (gazebo_ros/gzserver)
    gazebo_gui (gazebo_ros/gzclient)
    joint_state_controller_spawner (controller_manager/controller_manager)
    robot_state_publisher (robot_state_publisher/robot_state_publisher)
    spawn_gazebo_model (gazebo_ros/spawn_model)

ROS_MASTER_URI=http://localhost:11311

process[gazebo-1]: started with pid [30215]
process[gazebo_gui-2]: started with pid [30220]
process[spawn_gazebo_model-3]: started with pid [30225]
process[robot_state_publisher-4]: started with pid [30226]
process[fake_joint_calibration-5]: started with pid [30227]
process[joint_state_controller_spawner-6]: started with pid [30228]
process[arm_controller_spawner-7]: started with pid [30234]
[ INFO] [1533537658.257622922]: Finished loading Gazebo ROS API Plugin.
[ INFO] [1533537658.258576866]: waitForService: Service [/gazebo/set_physics_properties] has not been advertised, waiting...
[ INFO] [1533537658.301536599]: Finished loading Gazebo ROS API Plugin.
[ INFO] [1533537658.305363977]: waitForService: Service [/gazebo_gui/set_physics_properties] has not been advertised, waiting...
[INFO] [1533537658.818394, 0.000000]: Loading model XML from ros parameter robot_description
[INFO] [1533537658.823454, 0.000000]: Waiting for service /gazebo/spawn_urdf_model
[ INFO] [1533537659.269417707, 0.022000000]: waitForService: Service [/gazebo/set_physics_properties] is now available.
[ INFO] [1533537659.305982439, 0.057000000]: Physics dynamic reconfigure ready.
[INFO] [1533537659.427206, 0.174000]: Calling service /gazebo/spawn_urdf_model
[INFO] [1533537659.658381, 0.350000]: Spawn status: SpawnModel: Successfully spawned entity
[ INFO] [1533537659.686450804, 0.350000000]: Loading gazebo_ros_control plugin
[ INFO] [1533537659.686583384, 0.350000000]: Starting gazebo_ros_control plugin in namespace: /
[ INFO] [1533537659.687830607, 0.350000000]: gazebo_ros_control plugin is waiting for model URDF in parameter [robot_description] on the ROS param server.
[ERROR] [1533537659.800387980, 0.350000000]: No p gain specified for pid.  Namespace: /gazebo_ros_control/pid_gains/shoulder_pan_joint
[ERROR] [1533537659.800890942, 0.350000000]: No p gain specified for pid.  Namespace: /gazebo_ros_control/pid_gains/shoulder_lift_joint
[ERROR] [1533537659.801453146, 0.350000000]: No p gain specified for pid.  Namespace: /gazebo_ros_control/pid_gains/elbow_joint
[ERROR] [1533537659.801932840, 0.350000000]: No p gain specified for pid.  Namespace: /gazebo_ros_control/pid_gains/wrist_1_joint
[ERROR] [1533537659.802383934, 0.350000000]: No p gain specified for pid.  Namespace: /gazebo_ros_control/pid_gains/wrist_2_joint
[ERROR] [1533537659.803206864, 0.350000000]: No p gain specified for pid.  Namespace: /gazebo_ros_control/pid_gains/wrist_3_joint
[ INFO] [1533537659.807856409, 0.350000000]: Loaded gazebo_ros_control.
[spawn_gazebo_model-3] process has finished cleanly
log file: /home/profanter/.ros/log/aac53778-9943-11e8-9a5b-a44cc8ba95be/spawn_gazebo_model-3*.log
Loaded arm_controller
Loaded joint_state_controller
Started ['arm_controller'] successfully
Started ['joint_state_controller'] successfully
[arm_controller_spawner-7] process has finished cleanly
log file: /home/profanter/.ros/log/aac53778-9943-11e8-9a5b-a44cc8ba95be/arm_controller_spawner-7*.log
[joint_state_controller_spawner-6] process has finished cleanly
log file: /home/profanter/.ros/log/aac53778-9943-11e8-9a5b-a44cc8ba95be/joint_state_controller_spawner-6*.log

roslaunch ur5_moveit_config ur5_moveit_planning_execution.launch sim:=true

Checking log directory for disk usage. This may take awhile.
Press Ctrl-C to interrupt
Done checking log file disk usage. Usage is <1GB.

started roslaunch server http://pc1-n-094:41529/

SUMMARY
========

PARAMETERS
 * /move_group/allow_trajectory_execution: True
 * /move_group/capabilities: move_group/MoveGr...
 * /move_group/controller_list: [{'action_ns': 'f...
 * /move_group/endeffector/planner_configs: ['SBLkConfigDefau...
 * /move_group/jiggle_fraction: 0.05
 * /move_group/manipulator/longest_valid_segment_fraction: 0.01
 * /move_group/manipulator/planner_configs: ['SBLkConfigDefau...
 * /move_group/max_range: 5.0
 * /move_group/max_safe_path_cost: 1
 * /move_group/moveit_controller_manager: moveit_simple_con...
 * /move_group/moveit_manage_controllers: True
 * /move_group/octomap_resolution: 0.025
 * /move_group/planner_configs/BKPIECEkConfigDefault/border_fraction: 0.9
 * /move_group/planner_configs/BKPIECEkConfigDefault/failed_expansion_score_factor: 0.5
 * /move_group/planner_configs/BKPIECEkConfigDefault/min_valid_path_fraction: 0.5
 * /move_group/planner_configs/BKPIECEkConfigDefault/range: 0.0
 * /move_group/planner_configs/BKPIECEkConfigDefault/type: geometric::BKPIECE
 * /move_group/planner_configs/ESTkConfigDefault/goal_bias: 0.05
 * /move_group/planner_configs/ESTkConfigDefault/range: 0.0
 * /move_group/planner_configs/ESTkConfigDefault/type: geometric::EST
 * /move_group/planner_configs/KPIECEkConfigDefault/border_fraction: 0.9
 * /move_group/planner_configs/KPIECEkConfigDefault/failed_expansion_score_factor: 0.5
 * /move_group/planner_configs/KPIECEkConfigDefault/goal_bias: 0.05
 * /move_group/planner_configs/KPIECEkConfigDefault/min_valid_path_fraction: 0.5
 * /move_group/planner_configs/KPIECEkConfigDefault/range: 0.0
 * /move_group/planner_configs/KPIECEkConfigDefault/type: geometric::KPIECE
 * /move_group/planner_configs/LBKPIECEkConfigDefault/border_fraction: 0.9
 * /move_group/planner_configs/LBKPIECEkConfigDefault/min_valid_path_fraction: 0.5
 * /move_group/planner_configs/LBKPIECEkConfigDefault/range: 0.0
 * /move_group/planner_configs/LBKPIECEkConfigDefault/type: geometric::LBKPIECE
 * /move_group/planner_configs/PRMkConfigDefault/max_nearest_neighbors: 10
 * /move_group/planner_configs/PRMkConfigDefault/type: geometric::PRM
 * /move_group/planner_configs/PRMstarkConfigDefault/type: geometric::PRMstar
 * /move_group/planner_configs/RRTConnectkConfigDefault/range: 0.0
 * /move_group/planner_configs/RRTConnectkConfigDefault/type: geometric::RRTCon...
 * /move_group/planner_configs/RRTkConfigDefault/goal_bias: 0.05
 * /move_group/planner_configs/RRTkConfigDefault/range: 0.0
 * /move_group/planner_configs/RRTkConfigDefault/type: geometric::RRT
 * /move_group/planner_configs/RRTstarkConfigDefault/delay_collision_checking: 1
 * /move_group/planner_configs/RRTstarkConfigDefault/goal_bias: 0.05
 * /move_group/planner_configs/RRTstarkConfigDefault/range: 0.0
 * /move_group/planner_configs/RRTstarkConfigDefault/type: geometric::RRTstar
 * /move_group/planner_configs/SBLkConfigDefault/range: 0.0
 * /move_group/planner_configs/SBLkConfigDefault/type: geometric::SBL
 * /move_group/planner_configs/TRRTkConfigDefault/frountierNodeRatio: 0.1
 * /move_group/planner_configs/TRRTkConfigDefault/frountier_threshold: 0.0
 * /move_group/planner_configs/TRRTkConfigDefault/goal_bias: 0.05
 * /move_group/planner_configs/TRRTkConfigDefault/init_temperature: 10e-6
 * /move_group/planner_configs/TRRTkConfigDefault/k_constant: 0.0
 * /move_group/planner_configs/TRRTkConfigDefault/max_states_failed: 10
 * /move_group/planner_configs/TRRTkConfigDefault/min_temperature: 10e-10
 * /move_group/planner_configs/TRRTkConfigDefault/range: 0.0
 * /move_group/planner_configs/TRRTkConfigDefault/temp_change_factor: 2.0
 * /move_group/planner_configs/TRRTkConfigDefault/type: geometric::TRRT
 * /move_group/planning_plugin: ompl_interface/OM...
 * /move_group/planning_scene_monitor/publish_geometry_updates: True
 * /move_group/planning_scene_monitor/publish_planning_scene: True
 * /move_group/planning_scene_monitor/publish_state_updates: True
 * /move_group/planning_scene_monitor/publish_transforms_updates: True
 * /move_group/request_adapters: default_planner_r...
 * /move_group/start_state_max_bounds_error: 0.1
 * /move_group/trajectory_execution/allowed_execution_duration_scaling: 1.2
 * /move_group/trajectory_execution/allowed_goal_duration_margin: 0.5
 * /move_group/trajectory_execution/execution_duration_monitoring: False
 * /move_group/use_controller_manager: False
 * /robot_description_kinematics/manipulator/kinematics_solver: kdl_kinematics_pl...
 * /robot_description_kinematics/manipulator/kinematics_solver_attempts: 3
 * /robot_description_kinematics/manipulator/kinematics_solver_search_resolution: 0.005
 * /robot_description_kinematics/manipulator/kinematics_solver_timeout: 0.005
 * /robot_description_planning/joint_limits/elbow_joint/has_acceleration_limits: True
 * /robot_description_planning/joint_limits/elbow_joint/has_velocity_limits: True
 * /robot_description_planning/joint_limits/elbow_joint/max_acceleration: 3.15
 * /robot_description_planning/joint_limits/elbow_joint/max_velocity: 3.15
 * /robot_description_planning/joint_limits/shoulder_lift_joint/has_acceleration_limits: True
 * /robot_description_planning/joint_limits/shoulder_lift_joint/has_velocity_limits: True
 * /robot_description_planning/joint_limits/shoulder_lift_joint/max_acceleration: 3.15
 * /robot_description_planning/joint_limits/shoulder_lift_joint/max_velocity: 3.15
 * /robot_description_planning/joint_limits/shoulder_pan_joint/has_acceleration_limits: True
 * /robot_description_planning/joint_limits/shoulder_pan_joint/has_velocity_limits: True
 * /robot_description_planning/joint_limits/shoulder_pan_joint/max_acceleration: 3.15
 * /robot_description_planning/joint_limits/shoulder_pan_joint/max_velocity: 3.15
 * /robot_description_planning/joint_limits/wrist_1_joint/has_acceleration_limits: True
 * /robot_description_planning/joint_limits/wrist_1_joint/has_velocity_limits: True
 * /robot_description_planning/joint_limits/wrist_1_joint/max_acceleration: 3.2
 * /robot_description_planning/joint_limits/wrist_1_joint/max_velocity: 3.2
 * /robot_description_planning/joint_limits/wrist_2_joint/has_acceleration_limits: True
 * /robot_description_planning/joint_limits/wrist_2_joint/has_velocity_limits: True
 * /robot_description_planning/joint_limits/wrist_2_joint/max_acceleration: 3.2
 * /robot_description_planning/joint_limits/wrist_2_joint/max_velocity: 3.2
 * /robot_description_planning/joint_limits/wrist_3_joint/has_acceleration_limits: True
 * /robot_description_planning/joint_limits/wrist_3_joint/has_velocity_limits: True
 * /robot_description_planning/joint_limits/wrist_3_joint/max_acceleration: 3.2
 * /robot_description_planning/joint_limits/wrist_3_joint/max_velocity: 3.2
 * /robot_description_semantic: <?xml version="1....
 * /rosdistro: melodic
 * /rosversion: 1.14.2

NODES
  /
    move_group (moveit_ros_move_group/move_group)

ROS_MASTER_URI=http://localhost:11311

process[move_group-1]: started with pid [30876]
[ INFO] [1533537786.451732877]: Loading robot model 'ur5'...
[ WARN] [1533537786.452404050]: Skipping virtual joint 'fixed_base' because its child frame 'base_link' does not match the URDF frame 'world'
[ INFO] [1533537786.452431910]: No root/virtual joint specified in SRDF. Assuming fixed joint
[ INFO] [1533537786.476300421]: Loading robot model 'ur5'...
[ WARN] [1533537786.476345846]: Skipping virtual joint 'fixed_base' because its child frame 'base_link' does not match the URDF frame 'world'
[ INFO] [1533537786.476357261]: No root/virtual joint specified in SRDF. Assuming fixed joint
[ INFO] [1533537786.510397487]: Publishing maintained planning scene on 'monitored_planning_scene'
[ INFO] [1533537786.512233673]: MoveGroup debug mode is OFF
Starting context monitors...
[ INFO] [1533537786.512264526]: Starting scene monitor
[ INFO] [1533537786.514143437]: Listening to '/planning_scene'
[ INFO] [1533537786.514182631]: Starting world geometry monitor
[ INFO] [1533537786.517293087]: Listening to '/collision_object' using message notifier with target frame 'world '
[ INFO] [1533537786.519279999]: Listening to '/planning_scene_world' for planning scene world geometry
[ INFO] [1533537786.524654042]: Listening to '/attached_collision_object' for attached collision objects
Context monitors started.
[ INFO] [1533537786.550483794]: Initializing OMPL interface using ROS parameters
[ INFO] [1533537786.564761212]: Using planning interface 'OMPL'
[ INFO] [1533537786.567363203]: Param 'default_workspace_bounds' was not set. Using default value: 10
[ INFO] [1533537786.567798903]: Param 'start_state_max_bounds_error' was set to 0.1
[ INFO] [1533537786.568098827]: Param 'start_state_max_dt' was not set. Using default value: 0.5
[ INFO] [1533537786.568379433]: Param 'start_state_max_dt' was not set. Using default value: 0.5
[ INFO] [1533537786.568613514]: Param 'jiggle_fraction' was set to 0.05
[ INFO] [1533537786.568861706]: Param 'max_sampling_attempts' was not set. Using default value: 100
[ INFO] [1533537786.568905081]: Using planning request adapter 'Add Time Parameterization'
[ INFO] [1533537786.568921344]: Using planning request adapter 'Fix Workspace Bounds'
[ INFO] [1533537786.568935293]: Using planning request adapter 'Fix Start State Bounds'
[ INFO] [1533537786.568948937]: Using planning request adapter 'Fix Start State In Collision'
[ INFO] [1533537786.568964636]: Using planning request adapter 'Fix Start State Path Constraints'
[ INFO] [1533537787.020028301, 127.325000000]: Added FollowJointTrajectory controller for 
[ INFO] [1533537787.020179679, 127.325000000]: Returned 1 controllers in list
[ INFO] [1533537787.038130220, 127.343000000]: Trajectory execution is managing controllers
Loading 'move_group/ApplyPlanningSceneService'...
Loading 'move_group/ClearOctomapService'...
Loading 'move_group/MoveGroupCartesianPathService'...
Loading 'move_group/MoveGroupExecuteTrajectoryAction'...
Loading 'move_group/MoveGroupGetPlanningSceneService'...
Loading 'move_group/MoveGroupKinematicsService'...
Loading 'move_group/MoveGroupMoveAction'...
Loading 'move_group/MoveGroupPickPlaceAction'...
Loading 'move_group/MoveGroupPlanService'...
Loading 'move_group/MoveGroupQueryPlannersService'...
Loading 'move_group/MoveGroupStateValidationService'...
[ INFO] [1533537787.133816105, 127.439000000]: 

********************************************************
* MoveGroup using: 
*     - ApplyPlanningSceneService
*     - ClearOctomapService
*     - CartesianPathService
*     - ExecuteTrajectoryAction
*     - GetPlanningSceneService
*     - KinematicsService
*     - MoveAction
*     - PickPlaceAction
*     - MotionPlanService
*     - QueryPlannersService
*     - StateValidationService
********************************************************

[ INFO] [1533537787.133900241, 127.439000000]: MoveGroup context using planning plugin ompl_interface/OMPLPlanner
[ INFO] [1533537787.133937918, 127.439000000]: MoveGroup context initialization complete

You can start planning now!

roslaunch ur5_moveit_config moveit_rviz.launch config:=true

hecking log directory for disk usage. This may take awhile.
Press Ctrl-C to interrupt
Done checking log file disk usage. Usage is <1GB.

started roslaunch server http://pc1-n-094:44423/

SUMMARY
========

PARAMETERS
 * /rosdistro: melodic
 * /rosversion: 1.14.2
 * /rviz_pc1_n_094_30894_4378003656461834133/manipulator/kinematics_solver: kdl_kinematics_pl...
 * /rviz_pc1_n_094_30894_4378003656461834133/manipulator/kinematics_solver_attempts: 3
 * /rviz_pc1_n_094_30894_4378003656461834133/manipulator/kinematics_solver_search_resolution: 0.005
 * /rviz_pc1_n_094_30894_4378003656461834133/manipulator/kinematics_solver_timeout: 0.005

NODES
  /
    rviz_pc1_n_094_30894_4378003656461834133 (rviz/rviz)

ROS_MASTER_URI=http://localhost:11311

process[rviz_pc1_n_094_30894_4378003656461834133-1]: started with pid [30909]
[ INFO] [1533537791.639166091]: rviz version 1.13.1
[ INFO] [1533537791.639211981]: compiled against Qt version 5.9.5
[ INFO] [1533537791.639224265]: compiled against OGRE version 1.9.0 (Ghadamon)
libpng warning: iCCP: known incorrect sRGB profile
libpng warning: iCCP: known incorrect sRGB profile
[ INFO] [1533537792.172455630, 132.468000000]: Stereo is NOT SUPPORTED
[ INFO] [1533537792.173165167, 132.469000000]: OpenGl version: 4.6 (GLSL 4.6).
libpng warning: iCCP: known incorrect sRGB profile
[ INFO] [1533537795.448819144, 135.740000000]: Loading robot model 'ur5'...
[ WARN] [1533537795.448876936, 135.740000000]: Skipping virtual joint 'fixed_base' because its child frame 'base_link' does not match the URDF frame 'world'
[ INFO] [1533537795.448913503, 135.740000000]: No root/virtual joint specified in SRDF. Assuming fixed joint
[ INFO] [1533537795.476073929, 135.768000000]: Loading robot model 'ur5'...
[ WARN] [1533537795.476101482, 135.768000000]: Skipping virtual joint 'fixed_base' because its child frame 'base_link' does not match the URDF frame 'world'
[ INFO] [1533537795.476112052, 135.768000000]: No root/virtual joint specified in SRDF. Assuming fixed joint
[ INFO] [1533537795.543761234, 135.835000000]: Starting scene monitor
[ INFO] [1533537795.545602520, 135.837000000]: Listening to '/move_group/monitored_planning_scene'
[ INFO] [1533537795.788131702, 136.079000000]: Constructing new MoveGroup connection for group 'manipulator' in namespace ''
[ INFO] [1533537796.937293591, 137.227000000]: Ready to take commands for planning group manipulator.
[ INFO] [1533537796.937350589, 137.227000000]: Looking around: no
[ INFO] [1533537796.937376834, 137.227000000]: Replanning: no
[ WARN] [1533537796.951931285, 137.241000000]: Interactive marker 'EE:goal_ee_link' contains unnormalized quaternions. This warning will only be output once but may be true for others; enable DEBUG messages for ros.rviz.quaternions to see more details.

Please let me know if you need any more data/info!

Pro commented 6 years ago

If I enable the tf visualization in rviz, it also shows the correct frame position, only the robot model is not correct:

image

Pro commented 6 years ago

Note that I posted a more general question here https://answers.ros.org/question/299709/where-does-rvizmoveit-get-the-link-position/ I will keep both discussions in sync!

gavanderhoorn commented 6 years ago

@Pro wrote:

Note that I posted a more general question here https://answers.ros.org/question/299709/where-does-rvizmoveit-get-the-link-position/ I will keep both discussions in sync!

That was not really necessary: there is no magic topic, it's all TF.

Pro commented 6 years ago

That was not really necessary: there is no magic topic, it's all TF.

Ok, sorry! I wanted to keep the general discussion separated from the issue here, since I'm new in RViz+Gazebo, the question on answers.ros.org was more a general understanding question.

Could it be a universal_robot package configuration issue that RViz is not taking the correct tf data?

gavanderhoorn commented 6 years ago

At this point I don't know -- I've not migrated to Melodic.

have you changed anything in the ur_description package? Do things look normal if you run:

roslaunch ur_description ur5_upload.launch
roslaunch ur_description test.launch

The fact that the TF frames look normal seems to indicate this is purely a rendering issue.

Are both the visual and the collision geometry rendered like this?

Pro commented 6 years ago

The only thing I changed in the kinetic-devel branch is this here:

--- a/ur5_moveit_config/launch/move_group.launch
+++ b/ur5_moveit_config/launch/move_group.launch
@@ -50,7 +50,7 @@

     <!-- MoveGroup capabilities to load -->
     <param name="capabilities" value="move_group/MoveGroupCartesianPathService
-                                     move_group/MoveGroupExecuteService
+                                     move_group/MoveGroupExecuteTrajectoryAction
                                      move_group/MoveGroupKinematicsService
                                      move_group/MoveGroupMoveAction
                                      move_group/MoveGroupPickPlaceAction

otherwise you get the error:

[ERROR] [1533544519.838737300, 68.062000000]: Exception while loading move_group capability 'move_group/MoveGroupExecuteService': MultiLibraryClassLoader: Could not create class of type move_group::MoveGroupExecuteService
Available capabilities: move_group/ApplyPlanningSceneService, move_group/ClearOctomapService, move_group/MoveGroupCartesianPathService, move_group/MoveGroupExecuteService, move_group/MoveGroupExecuteTrajectoryAction, move_group/MoveGroupGetPlanningSceneService, move_group/MoveGroupKinematicsService, move_group/MoveGroupMoveAction, move_group/MoveGroupPickPlaceAction, move_group/MoveGroupPlanService, move_group/MoveGroupQueryPlannersService, move_group/MoveGroupStateValidationService

When I start your suggested test.launch it first fails with the following error: Fixed Frame [map] does not exist

image

This looks quite similar to the previous output where all the links are not correct. But now, if I set the fixed frame in global options from map to world at least the robot shows up correctly:

image

It looks like the moveit configuration is also using some invalid fixed frame and thus the model is not shown correctly.

Could it be related to the output here for the moveit_rviz.launch?

[ WARN] [1533545446.502632724, 10.010000000]: Skipping virtual joint 'fixed_base' because its child frame 'base_link' does not match the URDF frame 'world'
gavanderhoorn commented 6 years ago

The misconfigured fixed frame is expected, that is not a problem.

It looks like the moveit configuration is also using some invalid fixed frame and thus the model is not shown correctly.

No, those are not related, and it's also not the same concept.

Please don't make statements about causes unless you've verified them.


Edit: you could update the config of the fixed_base virtual joint in the MoveIt SRDF to see whether MoveIt under Melodic is more strict about this, but I don't remember this having changed.

gavanderhoorn commented 6 years ago

I won't have time to look at this more today or tomorrow unfortunately.

If you could try and see whether you can determine what is going on, that would be great.

Otherwise I can probably take a look later.

Pro commented 6 years ago

Not sure what I can change in the config for fixed_base... Unfortunately I'm a newbie in Gazebo+RViz+Ros Control so I really appreciate any help you could provide.

You can probably easily reproduce the issue by installing Ubuntu 18.04 in a VM and just install ros-melodic-desktop-full. Then cone this repo into a workspace.

ipa-nhg commented 6 years ago

@Pro thanks for testing UR with melodic.

Could you please take a screenshot of the collisions (the collisions are stl files instead of collada)? If the frames are right and the origins of the visual links are zero, looks like the problem is something with the 3D models(?).

I recommend just start rviz and the joint and robot state publisher like this:

roscd ur_description/urdf
roslaunch urdf_tutorial display.launch model:=ur5_robot.urdf.xacro gui:=true

Go to RobotModel disable "Visual enabled" and enable "Collision enabled" and please take a screenschot ( check also that the TF tag "Show axes" is enabled). Then press the button "Randomize" of the joint_state_publisher dialog and check RVIZ again.

did you test also the UR10 or the UR3?

Thanks a lot!!

Pro commented 6 years ago

@ipa-nhg thanks for your help! Here some screenshots:

If I run exactly the commands you provide, the output is this: image

So this looks OK to me.

Randomize also works as expected:

image.

So it looks to me that the models are correct and the issue is together with gazebo.

UR10 has the same issue when executing it together with Gazebo:

roslaunch ur_gazebo ur10.launch limited:=true
roslaunch ur10_moveit_config ur10_moveit_planning_execution.launch sim:=true limited:=true
roslaunch ur10_moveit_config moveit_rviz.launch config:=true

image

ipa-nhg commented 6 years ago

@pro Thanks a lot for the quick answer, can you please test this branch of my fork https://github.com/ipa-nhg/universal_robot/tree/MelodicHotFix ??

Please do not close the issue if this version solves the problem, it is just a Hot Fix and not a proper solution.

Pro commented 6 years ago

Unfortunately it's still the same with your version. The only difference is that the robot does not include any color now:

image

Pro commented 6 years ago

Could it be somehow related to an invalid fixed frame setting?

I.e. if I select an invalid fixed frame in RViz (without starting gazebo), the robot looks somehow similar to the broken one, when starting with gazebo. (as mentioned here: https://github.com/ros-industrial/universal_robot/issues/374#issuecomment-410637469)

So just a wild guess: When executing roslaunch ur5_moveit_config ur5_moveit_planning_execution.launch sim:=true limited:=true it shows the warning:

[ INFO] [1533565707.758143775]: Loading robot model 'ur5'...
[ WARN] [1533565707.758858906]: Skipping virtual joint 'fixed_base' because its child frame 'base_link' does not match the URDF frame 'world'
[ INFO] [1533565707.758873548]: No root/virtual joint specified in SRDF. Assuming fixed joint

And since the Scene Robot description is using the SRDF file for the /robot_description_semantic topic, there could be an issue with the SRDF file, that it does not define a valid root frame, and thus all the relative frame positions are set to 0,0,0.

Pro commented 6 years ago

Yayyy, found the issue:

It is in more detail described here: https://github.com/ros-planning/moveit/issues/690 and https://github.com/ros/urdfdom_headers/issues/41 and the PR https://github.com/ros/urdfdom_headers/pull/42

If you have a german locale setting, i.e. export LC_NUMERIC="de_DE.UTF-8" and then start RViz, you see the broken image. If you manually set the locale to export LC_NUMERIC="en_US.UTF-8" and then start RViz, everything is fine.

Note that the PR https://github.com/ros/urdfdom_headers/issues/41 is not (yet) included in the current melodic release.

gavanderhoorn commented 6 years ago

Ah, the locale issue.

Good find.

Thanks for reporting back.

sapan-ostic commented 5 years ago

How was the model appearing dark in gazebo solved? The RViz model loads up fine for me but Gazebo doesnt.

miguelprada commented 5 years ago

Hi @sapan-ostic, you already posted a similar question in another thread. Please don't post duplicate questions in unrelated issues and follow up there if you'd like further clarifications.

linzhuyue commented 5 years ago

@Pro Hi,I found the same error like you ,when i open bring up ur5 model in gazebo,it show a error position about the model,could you give me some information to fix this problem?