Why cant the Controller Spawner find the expected controller_manager ROS interface?
I have a quadruped robot with base link (BL), 4 child links called LFT,LFT, RFT,RFT, T for thigh and each having 4 children with name LFC,LBC,RFC,RBC, C for Calf. 8 joints - Base link to 4 thighs and 4 thighs to 4 calfs are used. An excerpt from the URDF is posted below:
<link
name="LFC">
<inertial>
<origin
xyz="0 -0.085 0" rpy="0 0 0" />
<mass value="0.038416" />
<inertia ixx="0.00010326" ixy="0" ixz="0" iyy="1.3494E-06" iyz="0" izz="0.00010451" />
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://urdfgenesyssw/meshes/LFC.STL" />
</geometry>
<material name=""> <color rgba="0.89804 0.91765 0.92941 1" />
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://urdfgenesyssw/meshes/LFC.STL" />
</geometry>
</collision>
</link>
A Joint and Transmission sample is also shown
<joint name="LFTLFC" type="revolute">
<origin xyz="0 -0.17 0.004" rpy="0 0 1.5708" />
<parent link="LFT" />
<child link="LFC" />
<axis xyz="0 0 1" />
<limit lower="-0.7854" upper="0.7854" effort="0" velocity="0" />
</joint>
<transmission name="LFTLFC_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="LFTLFC">
<hardwareInterface>EffortJointInterface</hardwareInterface>
</joint>
<actuator name="LFTLFC_motor">
<hardwareInterface>EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
Controllers are as shown below
# Publish all joint states -----------------------------------
joint_state_controller:
type: "joint_state_controller/JointStateController"
publish_rate: 50
# Position Controllers ---------------------------------------
LFTLFC_controller:
type: effort_controllers/JointPositionController
joint: LFTLFC
pid: {p: 100.0, i: 0.01, d: 10.0}
/gazebo_ros_control/pid_gains:
LFTLFC: {p: 100.0, i: 1.0, d: 10.0}
The launch part of the controllers is as follows:
<rosparam command="load" file="$(find urdfgenesyssw)/config/joints.yaml" ns="/urdfgenesyssw" />
<node name="controller_spawner" pkg="controller_manager" type="spawner" respawn="false" output="screen" ns="/urdfgenesyssw"
args="joint_state_controller
BLLFT_controller
LFTLFC_controller
BLLHT_controller
LHTLHC_controller
BLRFT_controller
RFTRFC_controller
BLRHT_controller
RHTRHC_controller
--timeout 30 " />
Why does the error show
[WARN] [1592642363.497903, 24.557000]: Controller Spawner couldn't find the expected controller_manager ROS interface.