Action client not connected when using MoveIt! with a real robot

asked 2018-04-12 07:32:48 -0500

znbrito gravatar image

updated 2018-04-18 03:46:45 -0500

Hi,

I am on Ubuntu 16.04 LTS and ROS Kinetic. Since I can use MoveIt! with Gazebo, I am now trying to use MoveIt! with a real the real robot. My main goal is to control a Robotis Manipulator-H that is standing on top of a Husky robot. My launch file for running MoveIt! in the Gazebo simulation is the following:

<?xml version="1.0"?>
<launch>

  <!-- Load the robot's joint names into the ROS parameter server -->
  <rosparam command="load" file="$(find husky_manipulator_h_moveit_config)/config/joint_names.yaml"/>

  <!-- Load the URDF, SRDF and other .yaml configuration files on the param server -->
  <include file="$(find husky_manipulator_h_moveit_config)/launch/planning_context.launch">
    <arg name="load_robot_description" value="true"/>
  </include>

  <!-- Publish joint states in the "/robotis_manipulator_h/joint_states" topic, since we now have a real robot simulated in Gazebo -->
  <node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher">
    <param name="/use_gui" value="false"/>
    <rosparam param="/source_list">[/robotis_manipulator_h/joint_states]</rosparam>
  </node>

  <!-- Given the published joint states, publish tf for the robot links -->
  <node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" respawn="true" output="screen" />

  <!-- Run the main MoveIt executable without trajectory execution (we do not have controllers configured by default) -->
  <include file="$(find husky_manipulator_h_moveit_config)/launch/move_group.launch">
    <arg name="publish_monitored_planning_scene" value="true"/>
  </include>

  <!-- Run Rviz and load the default config to see the state of the move_group node -->
  <include file="$(find husky_manipulator_h_moveit_config)/launch/moveit_rviz.launch">
    <arg name="config" value="true"/>
  </include>

  <!-- Load the sensor configuration for real time environment mapping, making it possible for the planner to avoid environment obstacles -->
  <arg name="frame" value="odom"/>
  <include file="$(find husky_manipulator_h_moveit_config)/launch/sensor_manager.launch.xml"> 
    <arg name="frame" value="$(arg frame)"/>
  </include>  

</launch>

Right now, my launch file for the real robot is the following:

<?xml version="1.0"?>
<launch>

  <!--Launch Robotis Controller -->
  <node name="robotis_manager" pkg="robotis_controller" type="robotis_manager" output="screen">     
    <rosparam command="load" file="$(find robotis_controller)/launch/ROBOTIS-manipulatorH.yaml" />
    <rosparam param="joint_state_publish_rate">125</rosparam> 
    <rosparam param="publish_joint_topic_name">"/robotis_manipulator_h/joint_states"</rosparam> <!-- Was originally "/joint_states" -->
    <rosparam param="subscribe_joint_topic_name">"/controller_joint_states"</rosparam> 
  </node>

    <!-- Load the robot's joint names into the ROS parameter server -->
  <rosparam command="load" file="$(find husky_manipulator_h_moveit_config)/config/joint_names.yaml"/>

  <!--<include file="$(find industrial_robot_simulator)/launch/robot_interface_simulator.launch" >
    <remap from="feedback_states" to="/robotis_manipulator_h/joint_states" />
  </include>-->

  <!-- Run the main MoveIt executable without trajectory execution (we do not have controllers configured by default) -->
  <include file="$(find husky_manipulator_h_moveit_config)/launch/move_group.launch">
    <arg name="publish_monitored_planning_scene" value="true"/>
  </include>

  <!-- Load the URDF, SRDF and other .yaml configuration files on the param server -->
  <include file="$(find husky_manipulator_h_moveit_config)/launch/planning_context.launch">
    <arg name="load_robot_description" value="true"/>
  </include>

  <!-- Given the published joint states, publish tf for the robot links and TF-->
  <node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" respawn="true" output="screen">
    <remap from="/joint_states" to="/robotis_manipulator_h/joint_states"/>
  </node>

  <!-- Launch Robot Initializer initial the robot by seting the torque control parameter to be true-->
  <node pkg="cat_manipulator_control" type="my_init_robot" name="init_robot" output="log"/> 

  <!-- Load the MoveIt! controller -->
  <arg name="manipulator_h_control_yaml_file" default="$(find manipulator_h_gazebo)/config/position_controller.yaml"/>
  <rosparam command="load" file="$(arg manipulator_h_control_yaml_file)" />  
  <node name="controller_spawner" pkg="controller_manager" type="spawner" respawn="false" output ...
(more)
edit retag flag offensive close merge delete

Comments

hi, did you find a solution for this? im having the same problem

pazgenie gravatar image pazgenie  ( 2019-05-07 03:41:11 -0500 )edit