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

Revision history [back]

click to hide/show revision 1
initial version
  1. Make sure that the urdf for the MoveIt Assistant was created out of schunk_hardware_config/powerball/urdf/powerball.urdf.xacro
  2. Try this launch file:

    I just took schunk_bringup/components/powerball_solo.launch and put it into your moveit_planning_execution_real.launch but I commented out the "upload joint configuration" part.(It uploads schunk_default_config/config/powerball_joint_configurations.yaml to the parameter server. But this yaml has a different joint config. And MoveIt already does this for you.)

    <launch>

    <!-- upload robot_description -->
            <include file="$(find schunk_hardware_config)/powerball/urdf/upload_powerball.launch" />
    
    <!-- start robot_state_publisher -->
    <node pkg="robot_state_publisher" type="state_publisher" name="robot_state_publisher"/>
    
    <!-- upload joint configuration 
    <include file="$(find schunk_default_config)/launch/upload_param_powerball.launch" /> -->
    
    <!-- start arm  -->
    <include file="$(find schunk_bringup)/components/powerball.launch" />
    
    
    <include file="$(find powerball_moveit)/launch/move_group.launch">
    <arg name="publish_monitored_planning_scene" value="true" />
    </include>
    
    <include file="$(find powerball_moveit)/launch/moveit_rviz.launch"/>
    
    <rosparam command="load" file="$(find powerball_moveit)/config/joint_names.yaml"/>
    

    </launch>

  3. Check your controllers.yaml formatting.

  4. If this doesn't work recursively check all launch files called by powerball.launch for parameter server uploads (yaml files) you don't need.

  1. Make sure that the urdf for the MoveIt Assistant was created out of schunk_hardware_config/powerball/urdf/powerball.urdf.xacro
  2. Try this launch file:

    I just took schunk_bringup/components/powerball_solo.launch and put it into your moveit_planning_execution_real.launch but I commented out the "upload joint configuration" part.(It uploads schunk_default_config/config/powerball_joint_configurations.yaml to the parameter server. But this yaml has a different joint config. And MoveIt already does this for you.)

    <launch>

    <!-- upload robot_description -->
            <include file="$(find schunk_hardware_config)/powerball/urdf/upload_powerball.launch" />
    
    <!-- start robot_state_publisher -->
    <node pkg="robot_state_publisher" type="state_publisher" name="robot_state_publisher"/>
    
    <!-- upload joint configuration 
    <include file="$(find schunk_default_config)/launch/upload_param_powerball.launch" /> -->
    
    <!-- start arm  -->
    <include file="$(find schunk_bringup)/components/powerball.launch" />
    
    
    <include file="$(find powerball_moveit)/launch/move_group.launch">
    <arg name="publish_monitored_planning_scene" value="true" />
    </include>
    
    <include file="$(find powerball_moveit)/launch/moveit_rviz.launch"/>
    
    <rosparam command="load" file="$(find powerball_moveit)/config/joint_names.yaml"/>
    

    </launch>

  3. Check your controllers.yaml formatting.

  4. If this doesn't work recursively check all launch files called by powerball.launch for parameter server uploads (yaml files) you don't need.

  5. Can you post your moveit_controller_manager.launch.

    Make sure you have disabled the controller_manager.

My moveit_controller_manager.launch

<launch>
  <arg name="moveit_controller_manager"
       default="pr2_moveit_controller_manager/Pr2MoveItControllerManager"/>
  <param name="moveit_controller_manager"
         value="$(arg moveit_controller_manager)"/>

  <arg name="controller_manager_name"
       default="pr2_controller_manager" />
  <param name="controller_manager_name"
         value="$(arg controller_manager_name)"/>

  <arg name="use_controller_manager" default="false" />
  <param name="use_controller_manager"
         value="$(arg use_controller_manager)" />

  <rosparam file="$(find kurtana_moveit_config)/config/controllers.yaml"/>
</launch>

My controllers.yaml

 controller_manager_ns:
    pr2_controller_manager
    controller_list:
      - name: "katana_arm_controller"
        ns: follow_joint_trajectory
        default: true
        joints:
           - katana_motor1_pan_joint
           - katana_motor2_lift_joint
           - katana_motor3_lift_joint
           - katana_motor4_lift_joint
           - katana_motor5_wrist_roll_joint

In your error message the joint "arm_controller" is not found. Somehow the controller name definition is parsed as a joint definition. You could try another name in your controllers.yaml and check how the error changes. Perhaps just make a completely new controllers.yaml.