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

Interactive markers does not appear on Moveit only for my custom robot

asked 2016-12-02 08:48:04 -0500

peter1234 gravatar image

updated 2016-12-13 08:00:52 -0500

After I import the package to Moveit I cant see Interactive markers to my robot so I can't execute a motion plan. I have checked urdf with check_urdf, I can move all links on Moveit Setup Assistant and all looks ok. I start Rviz with roslaunch '/home/student/Desktop/robot_moveit_config/launch/demo.launch' I export files from Moveit Setup Assistant to Desktop then I move folder to /opt/ros/indigo/share , I do roslaunch /opt/ros/indigo/share/assem5_moveit_config/launch/demo.launch Markers appeared one time but not again after re-export, am I doing right way?

[Screenshoots, Robot, Moveit setup assistant.] ( https://postimg.org/gallery/pcyvpyvk/ )

SRDF:

  <robot name="Assem5.SLDASM">
    <group name="arms"><link name="link_1"/>
       <link name="link_2"/>
      <link name="link_3"/>
      <link name="link_4"/>
      <link name="link_5_tool"/>
    </group>
    <group_state name="pose_0" group="arms">
      <joint name="joint_1" value="0"/>
      <joint name="joint_2" value="0"/>
      <joint name="joint_3" value="0"/>
      <joint name="joint_4" value="0"/>
      <joint name="joint_5_tool" value="0"/>
    </group_state>
    <end_effector name="end_effector_link 5" parent_link="link_4" group="arms"/>
    <virtual_joint name="base_joint_virtual_link" type="fixed" parent_frame="world_frame" child_link="base_link"/>

Information when i upload it to Moveit:

[ INFO] [1480689682.201512724]: MoveGroup context using planning plugin ompl_interface/OMPLPlanner
[ INFO] [1480689682.201602195]: MoveGroup context initialization complete
All is well! Everyone is happy! You can start planning now!
Registered event listener change listener:  true 
[ INFO] [1480689683.789499562]: Loading robot model 'Assem5.SLDASM'...
[ WARN] [1480689683.935955978]: Could not identify parent group for end-effector 'end_effector_link 5' 
[ INFO] [1480689684.093612791]: Loading robot model 'Assem5.SLDASM'...
[ WARN] [1480689684.233352057]: Could not identify parent group for end-effector 'end_effector_link 5'
[ WARN] [1480689684.233805597]: The root link base_link has an inertia specified in the URDF, but KDL does not support a root link with an inertia.  As a workaround, you can add an extra dummy link to your URDF.
[ INFO] [1480689684.818941731]: Starting scene monitor
[ INFO] [1480689684.826124575]: Listening to '/move_group/monitored_planning_scene'
[ INFO] [1480689685.533798626]: No active joints or end effectors found for group ''. Make sure you have defined an end effector in your SRDF file and that kinematics.yaml is loaded in this node's namespace.
[ INFO] [1480689685.534217491]: No active joints or end effectors found for group 'arms'. Make sure you have defined an end effector in your SRDF file and that kinematics.yaml is loaded in this node's namespace.
[ WARN] [1480689685.534651803]: The root link base_link has an inertia specified in the URDF, but KDL does not support a root link with an inertia.  As a workaround, you can add an extra dummy link to your URDF.
[ INFO] [1480689685.541682110]: No active joints or end effectors found for group 'arms'. Make sure you have defined an end effector in your SRDF file and that kinematics.yaml is loaded in this node's namespace.
[ INFO] [1480689685.544602709]: Constructing new MoveGroup connection for group 'arms' in namespace ''
[ INFO] [1480689686.447761196]: Ready to take MoveGroup commands for group arms.
[ INFO] [1480689686.447874546]: Looking around: no
[ INFO] [1480689686.447957077]: Replanning: no

Update 1:

[Robot structure] ( https://s24.postimg.org/a3zd9atid/rob ... (more)

edit retag flag offensive close merge delete

Comments

Do you have a gripper in your robot? If so, it should be created as a seperate group and should be added to the end effector in the moveit dialog. What is the launch file you are using?

Gokul gravatar image Gokul  ( 2016-12-07 08:49:31 -0500 )edit

I do not have gripper/tool there is only the active links. The launch file is demo.launch I updated the question (cant mark it as code). The folder with URDF and exported package from Moveit Setup assistant is one desktop. I tried with PR2 like on tutorial but there is no interactive marker.

peter1234 gravatar image peter1234  ( 2016-12-07 10:16:36 -0500 )edit

But the official exported package on opt/ros/indigo/share/PR2_moveit_config is working well.

peter1234 gravatar image peter1234  ( 2016-12-07 10:22:31 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
0

answered 2016-12-08 00:31:13 -0500

Gokul gravatar image

You didn't follow the moveit setup assistant tutorial properly.You have defined links for the "arms" group in setup assistant ,but you didn't define the joints for the same group. That is the reason your srdf doesn't have any joints defined in the arms group. Then you should define the kinematic solver for arms group by double clicking the name of the group in planning group dialog.

image description

Next create a seperate group for your tool joint and define the kinematic solver as none for this. Then make this group as the end effector group and the parent group of the end effector as arms group. This will resolve this warning

No active joints or end effectors found for group 'arms'. Make sure you have defined an end effector in your SRDF file and that kinematics.yaml is loaded in this node's namespace.

After fixing this, run demo.launch and you can see the interactive markers. For additional information, follow the steps in this Moveit tutorial .

edit flag offensive delete link more

Comments

I tried this tutorial and it is working but after I tried again and this error appeared:

Invalid <arg> tag: pr2_generated
ROS path [0]=/opt/ros/indigo/share/ros
ROS path [1]=/opt/ros/indigo/share
ROS path [2]=/opt/ros/indigo/stacks.
peter1234 gravatar image peter1234  ( 2016-12-09 11:14:05 -0500 )edit

Arg xml is <arg default="$(find pr2_generated)/default_warehouse_mongo_db" name="db_path"/> The traceback for the exception was written to the log file

peter1234 gravatar image peter1234  ( 2016-12-09 11:14:36 -0500 )edit

Delete the packages and reinstall it ,then run. It might be denoting a wrong path sometimes.

Gokul gravatar image Gokul  ( 2016-12-12 04:15:55 -0500 )edit

I export package form Moveit Setup Assistant to desktop then I move it to /opt/ros/indigo/share Then I do roslaunch '/opt/ros/indigo/share/assem5_moveit_config/launch/demo.launch' Markers appeared one time but not again after re-export with same setup, am I doing right way?

peter1234 gravatar image peter1234  ( 2016-12-13 04:49:55 -0500 )edit

install the package moveit tutorials in local workspace and try it. I think it will fix this issue

Gokul gravatar image Gokul  ( 2016-12-13 05:22:30 -0500 )edit

The local work space is the catkin folder or /opt/ros/indigo/share ?

peter1234 gravatar image peter1234  ( 2016-12-13 05:34:06 -0500 )edit

catkin folder

Gokul gravatar image Gokul  ( 2016-12-13 06:34:14 -0500 )edit

I have never used catkin workspace just /opt/ros/indigo/share/ I hope to fix it..

peter1234 gravatar image peter1234  ( 2016-12-13 07:24:22 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2016-12-02 08:47:40 -0500

Seen: 1,907 times

Last updated: Dec 13 '16