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

Rviz "No planning library loaded"

asked 2014-09-16 04:32:18 -0500

bjem85 gravatar image

Hi All,

I am following through the Moveit! Industrial Robot Tutorial and have got stuck at Part 3.1.2. I have copied the template launch file and minimally modified it for my own ends, but I have some questions:

There is a part of the <robot>_moveit_config moveit_planning_execution.launch that deals with the 'real' robot interface. Is this a node I need to write myself? I already have a means of publishing the joint angles of the robot to a sensor_msgs/JointState topic. My robot uses hydraulic rams so the joint angles are converted to ram lengths which are sent to a PID controller that takes in a sensor_msgs/JointState error and converts it to an effort that is then relayed to the robot valves. I'm a little lost about what sort of node I need to write to accept commands from the move_group node. As a starting point, I would like to have a planned trajectory as an input.

Here is the real robot-specific part of the launch file: <group unless="$(arg sim)"> <include file="$(find [robot_interface_pkg])/launch/robot_interface.launch" &gt;="" <arg="" name="robot_ip" value="$(arg robot_ip)"/> </include> </group>

The other problem I have is that the inverse kinematics don't seem to work properly. While I can drag the arm around, I cannot plan a path from one point to another. RViz says there is no planning library loaded and on the console I get the following message:

[ INFO] [1410858518.526968209]: Constructing new MoveGroup connection for group 'xyz_control'
[ERROR] [1410858548.853118450]: Unable to connect to move_group action server within allotted time (2)

Here is my RViz screen as I see it. Note that the tutorial implies I should be able to drag the robot around and plan paths with it. However I cannot plan paths with it.

image description

And here is my ROS graph from rqt_graph:

image description

The lack of planning library could be an issue with changing from the 'fake' controller manager to the 'simple' controller manager. Is this an issue? Here's a diff of controllers.yaml between where RViz was able to find a planning library and when it wasn't.

@@ -1,9 +1,9 @@
 <launch>

   <!-- Set the param that trajectory_execution_manager needs to find the controller plugin -->
-  <param name="moveit_controller_manager" value="moveit_fake_controller_manager/MoveItFakeControllerManager"/>
+  <param name="moveit_controller_manager" value="moveit_simple_controller_manager/MoveitSimpleControllerManager"/>

   <!-- The rest of the params are specific to this plugin -->
-  <rosparam file="$(find hyd_sys_complete_sldasm_moveit_config)/config/fake_controllers.yaml"/>
+  <rosparam file="$(find hyd_sys_complete_sldasm_moveit_config)/config/controllers.yaml"/>

 </launch>

Note there is also an IKFast inverse kinematics plugin I have generated that has to fit into the mix somewhere. What is the best way to proceed? I want to be able to plan paths of the robot using Section 3 of the tutorial. There are a few pieces to this puzzle and I haven't quite worked out how they all go together at this stage.

Kind Regards Bart

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
1

answered 2014-09-17 21:52:38 -0500

First, I recommend that you try to get your robot path planning working using demo.launch (this file is generate using the moveit setup assistant). This is a self-contained moveit launch which should help you debug the planner and IK problems.

Once this is working, you will need to create ROS nodes that connect to the real robot. There are multiple ways to achieve this. At a conceptual level you need a way to read the robot state and a way to send trajectories. One option is to utilize ros control - I don't have much experience with this. ROS-Industrial robots publish joint states via ROS topics and execute trajectories using the joint_trajectory_action in the industrial_robot_client). The template you are using assumes a ROS-Industrial approach.

edit flag offensive delete link more

Comments

The demo.launch worked fine immediately. I also can publish the actual robot joint state to /tf. So I'm happy with that. There's a controller that has PID parameters in a .yaml file (I can't remember the name), which is like what I want to use but I could not work out how to implement it.

bjem85 gravatar image bjem85  ( 2014-09-18 03:00:56 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2014-09-16 04:32:18 -0500

Seen: 2,909 times

Last updated: Sep 17 '14