ROS2 controller manager migration from foxy to humble: controller manager not available
This question is related to the following one: https://answers.ros.org/question/412742/controller-manager-not-available-in-ros2/
The described answer is not working in my case.
Edit 2:
Short version for everyone trying:
git clone https://git.fh-aachen.de/mascor-public/leo_simulator
git clone https://git.fh-aachen.de/mascor-public/leo-common-ros2
build it and run
ros2 launch leo_gazebo leo_gazebo.launch.py
This will end in the error "controller manager not available".
Long version:
Here is my launch file:
from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument
from launch.substitutions import LaunchConfiguration, Command
from launch_ros.actions import Node, PushRosNamespace
def generate_launch_description():
pkg_share = get_package_share_directory("leo_gazebo")
leo_description_share = get_package_share_directory("leo_description")
return LaunchDescription(
[
DeclareLaunchArgument(
name="model",
default_value=[leo_description_share, "/urdf/leo_sim.urdf.xacro"],
description="Absolute path to robot urdf.xacro file",
),
DeclareLaunchArgument(
name="fixed",
default_value="false",
description='Set to "true" to spawn the robot fixed to the world',
),
DeclareLaunchArgument(
name="robot_ns", default_value="/", description="Namespace of the robot"
),
DeclareLaunchArgument(
name="model_name",
default_value="leo",
description="The name of the spawned model in Gazebo",
),
PushRosNamespace(LaunchConfiguration("robot_ns")),
Node(
name="robot_state_publisher",
package="robot_state_publisher",
executable="robot_state_publisher",
parameters=[
{
"robot_description": Command(
[
"xacro ",
LaunchConfiguration("model"),
" fixed:=",
LaunchConfiguration("fixed"),
]
)
}
],
),
Node(
name="spawn_entity",
package="gazebo_ros",
executable="spawn_entity.py",
# fmt: off
arguments=[
"-topic", "robot_description",
"-entity", LaunchConfiguration("model_name"),
],
# fmt: on
),
Node(
name="joint_state_broadcaster_spawner",
package="controller_manager",
executable="spawner",
arguments=["joint_state_broadcaster", "--controller-manager", "/controller_manager"],
),
Node(
name="diff_drive_controller_spawner",
package="controller_manager",
executable="spawner",
arguments=["diff_drive_controller", "--controller-manager", "/controller_manager"],
),
]
)
And this is the error log after launching it:
[INFO] [launch]: All log files can be found below /home/patrick/.ros/log/2023-03-09-12-12-04-729782-dell-10526
[INFO] [launch]: Default logging verbosity is set to INFO
[INFO] [gzserver-1]: process started with pid [10528]
[INFO] [gzclient-2]: process started with pid [10530]
[INFO] [robot_state_publisher-3]: process started with pid [10532]
[INFO] [spawn_entity.py-4]: process started with pid [10534]
[INFO] [spawner-5]: process started with pid [10536]
[INFO] [spawner-6]: process started with pid [10538]
[robot_state_publisher-3] [INFO] [1678360327.041513962] [robot_state_publisher]: got segment antenna_link
[robot_state_publisher-3] [INFO] [1678360327.041788561] [robot_state_publisher]: got segment base_footprint
[robot_state_publisher-3] [INFO] [1678360327.041826152] [robot_state_publisher]: got segment base_link
[robot_state_publisher-3] [INFO] [1678360327.041848917] [robot_state_publisher]: got segment camera_frame
[robot_state_publisher-3] [INFO] [1678360327.041869751] [robot_state_publisher]: got segment camera_optical_frame
[robot_state_publisher-3] [INFO] [1678360327.041891126] [robot_state_publisher]: got segment imu_frame
[robot_state_publisher-3] [INFO] [1678360327.041911788] [robot_state_publisher]: got segment rocker_L_link
[robot_state_publisher-3] [INFO] [1678360327.041932055] [robot_state_publisher]: got segment rocker_R_link
[robot_state_publisher-3] [INFO] [1678360327.041951416] [robot_state_publisher]: got segment wheel_FL_link
[robot_state_publisher-3] [INFO] [1678360327.041971515] [robot_state_publisher]: got segment wheel_FR_link
[robot_state_publisher-3] [INFO] [1678360327.041991344] [robot_state_publisher]: got segment wheel_RL_link
[robot_state_publisher-3] [INFO] [1678360327.042011296] [robot_state_publisher]: got segment wheel_RR_link
[spawn_entity.py-4] [INFO] [1678360327.554963416] [spawn_entity]: Spawn Entity started
[spawn_entity.py-4] [INFO] [1678360327.555265999] [spawn_entity]: Loading entity published on topic robot_description
[spawn_entity.py-4] /opt/ros/humble/local/lib/python3.10/dist-packages/rclpy/qos.py:307: UserWarning: DurabilityPolicy.RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL is deprecated. Use DurabilityPolicy.TRANSIENT_LOCAL instead.
[spawn_entity.py-4] warnings.warn(
[spawn_entity.py-4] [INFO] [1678360327.561197332] [spawn_entity]: Waiting for entity xml on robot_description
[spawn_entity.py-4] [INFO] [1678360327.573506918] [spawn_entity]: Waiting for service /spawn_entity, timeout = 30
[spawn_entity.py-4] [INFO] [1678360327.573778448] [spawn_entity]: Waiting for service /spawn_entity
[spawner-6] [INFO] [1678360329.436630319] [diff_drive_controller_spawner]: Waiting for '/controller_manager' node to exist
[spawner-5] [INFO] [1678360329.444134048] [joint_state_broadcaster_spawner]: Waiting for '/controller_manager' node to exist
[spawner-6] [INFO] [1678360331.457972133] [diff_drive_controller_spawner]: Waiting for '/controller_manager' node to exist
[spawner-5] [INFO] [1678360331.461007411] [joint_state_broadcaster_spawner]: Waiting for '/controller_manager' node to exist
[spawn_entity.py-4] [INFO] [1678360332.843765895] [spawn_entity]: Calling service /spawn_entity
[spawner-6] [INFO] [1678360333.472033590] [diff_drive_controller_spawner]: Waiting for '/controller_manager' node to exist
[spawner-5] [INFO] [1678360333.474280001] [joint_state_broadcaster_spawner]: Waiting for '/controller_manager' node to exist
[spawn_entity.py-4] [INFO] [1678360333.797064145] [spawn_entity]: Spawn status: SpawnEntity: Successfully spawned entity [leo]
[INFO] [spawn_entity.py-4]: process has finished cleanly [pid 10534]
[spawner-6] [INFO] [1678360335.484502457] [diff_drive_controller_spawner]: Waiting for '/controller_manager' node to exist
[spawner-5] [INFO] [1678360335.486055845] [joint_state_broadcaster_spawner]: Waiting for '/controller_manager' node to exist
[spawner-6] [ERROR] [1678360337.503889166] [diff_drive_controller_spawner]: Controller manager not available
[spawner-5] [ERROR] [1678360337.506222462] [joint_state_broadcaster_spawner]: Controller manager not available
[ERROR] [spawner-6]: process has died [pid 10538, exit code 1, cmd '/opt/ros/humble/lib/controller_manager/spawner diff_drive_controller --controller-manager /controller_manager --ros-args -r __node:=diff_drive_controller_spawner -r __ns:=/'].
[ERROR] [spawner-5]: process has died [pid 10536, exit code 1, cmd '/opt/ros/humble/lib/controller_manager/spawner joint_state_broadcaster --controller-manager /controller_manager --ros-args -r __node:=joint_state_broadcaster_spawner -r __ns:=/'].
[gzserver-1] [INFO] [1678360394.041623927] [rocker_differential]: DifferentialPlugin loaded! Joint A: "rocker_L_joint", Joint B: "rocker_R_joint", Force Constant: 100
[gzserver-1] [INFO] [1678360394.074408720] [gazebo_ros2_control]: Loading gazebo_ros2_control plugin
[gzserver-1] [INFO] [1678360394.076920473] [gazebo_ros2_control]: Starting gazebo_ros2_control plugin in namespace: /
[gzserver-1] [INFO] [1678360394.076967370] [gazebo_ros2_control]: Starting gazebo_ros2_control plugin in ros 2 node: gazebo_ros2_control
[gzserver-1] [INFO] [1678360394.077022296] [gazebo_ros2_control]: Loading parameter files package://leo_description/config/controllers.yaml
[gzserver-1] [ERROR] [1678360394.077189945] [gazebo_ros2_control]: parser error Couldn't parse params file: '--params-file package://leo_description/config/controllers.yaml'. Error: Error opening YAML file, at ./src/parser.c:270, at ./src/rcl/arguments.c:406
Edit 1:
leo_sim.urdf.xacro
<?xml version="1.0"?>
<robot xmlns:xacro="http://ros.org/wiki/xacro"
name="leo_sim">
<xacro:arg name="fixed" default="false"/>
<xacro:arg name="robot_ns" default=""/>
<xacro:include filename="$(find leo_description)/urdf/macros.xacro"/>
<xacro:leo_sim robot_ns="$(arg robot_ns)"
fixed="$(arg fixed)"/>
</robot>
And macros.xacro
<?xml version="1.0" encoding="utf-8"?>
<xacro:macro name="rocker_link" params="name">
<link name="${link_prefix}rocker_${name}_link">
<inertial>
<mass value="1.387336"/>
<origin xyz="0 0.01346 -0.06506"/>
<inertia
ixx="0.002956" ixy="-0.000001489324" ixz="-0.000008103407"
iyy="0.02924" iyz="0.00007112"
izz="0.02832"/>
</inertial>
<visual>
<geometry>
<mesh filename="package://leo_description/models/Rocker.dae"/>
</geometry>
</visual>
<collision>
<geometry>
<mesh filename="package://leo_description/models/Rocker_outline.stl"/>
</geometry>
</collision>
</link>
</xacro:macro>
<xacro:macro name="wheel_link" params="name model">
<link name="${link_prefix}wheel_${name}_link">
<inertial>
<mass value="0.283642"/>
<origin xyz="0 0.030026 0"/>
<inertia
ixx="0.000391" ixy="0.00000123962" ixz="5.52582e-7"
iyy="0.0004716" iyz="-0.000002082042"
izz="0.000391"/>
</inertial>
<visual>
<geometry>
<mesh filename="package://leo_description/models/Wheel${model}.dae"/>
</geometry>
</visual>
<collision>
<origin xyz="0 0.04485 0" rpy="${pi/2} 0 0"/>
<geometry>
<cylinder radius="0.057" length="0.07"/>
</geometry>
</collision>
<collision>
<origin xyz="0 0.04485 0" rpy="${pi/2} 0 0"/>
<geometry>
<cylinder radius="0.0625" length="0.04"/>
</geometry>
</collision>
<collision>
<geometry>
<mesh filename="package://leo_description/models/Wheel_outline.stl"/>
</geometry>
</collision>
</link>
</xacro:macro>
<!-- LINKS -->
<xacro:if value="${footprint_link}">
<link name="${link_prefix}base_footprint"/>
</xacro:if>
<link name="${link_prefix}base_link">
<inertial>
<mass value="1.584994"/>
<origin xyz="-0.019662 0.011643 -0.031802"/>
<inertia
ixx="0.01042" ixy="0.001177" ixz="-0.0008871"
iyy="0.01045" iyz="0.0002226"
izz="0.01817"/>
</inertial>
<visual>
<geometry>
<mesh filename="package://leo_description/models/Chassis.dae"/>
</geometry>
</visual>
<collision>
<geometry>
<mesh filename="package://leo_description/models/Chassis_outline.stl"/>
</geometry>
</collision>
</link>
<xacro:rocker_link name="L"/>
<xacro:rocker_link name="R"/>
<xacro:wheel_link name="FL" model="A"/>
<xacro:wheel_link name="RL" model="A"/>
<xacro:wheel_link name="FR" model="B"/>
<xacro:wheel_link name="RR" model="B"/>
<xacro:if value="${default_antenna}">
<link name="${link_prefix}antenna_link">
<inertial>
<mass value="0.001237"/>
<origin xyz="0 0 0.028828"/>
<inertia
ixx="2.5529e-7" ixy="0.0" ixz="0.0"
iyy="2.5529e-7" iyz="0.0"
izz="1.354e-8"/>
</inertial>
<visual>
<geometry>
<mesh filename="package://leo_description/models/Antenna.dae"/>
</geometry>
</visual>
<collision>
<origin xyz="0 0 0.028"/>
<geometry>
<cylinder radius="0.0055" length="0.056"/>
</geometry>
</collision>
</link>
</xacro:if>
<link name="${link_prefix}camera_frame"/>
<link name="${link_prefix}camera_optical_frame"/>
<link name="${link_prefix}imu_frame"/>
<!-- JOINTS -->
<xacro:if value="${footprint_link}">
<joint name="${joint_prefix}base_joint" type="fixed">
<origin xyz="0 0 0.19783" rpy="0 0 0"/>
<parent link="${link_prefix}base_footprint"/>
<child link="${link_prefix}base_link"/>
</joint>
</xacro:if>
<xacro:if value="${rockers_fixed}">
<xacro:property name="rockers_joint_type" value="fixed"/>
</xacro:if>
<xacro:unless value="${rockers_fixed}">
<xacro:property name="rockers_joint_type" value="revolute"/>
</xacro:unless>
<joint name="${joint_prefix}rocker_L_joint" type="${rockers_joint_type}">
<origin xyz="0.00263 0.14167 -0.04731" rpy="0 0 ${pi}"/>
<parent link="${link_prefix}base_link"/>
<child link="${link_prefix}rocker_L_link"/>
<axis xyz="0 1 0"/>
<limit effort="100.0" lower="-0.24" upper="0.24" velocity="100.0"/>
<dynamics friction="1.0" damping="0.1"/>
</joint>
<joint name="${joint_prefix}rocker_R_joint" type="${rockers_joint_type}">
<origin xyz="0.00263 -0.14167 -0.04731" rpy="0 0 0"/>
<parent link="${link_prefix}base_link"/>
<child link="${link_prefix}rocker_R_link"/>
<axis xyz="0 1 0"/>
<limit effort="100.0" lower="-0.24" upper="0.24" velocity="100.0"/>
<dynamics friction="1.0" damping="0.1"/>
<mimic joint="rocker_L_joint"/>
</joint>
<joint name="${joint_prefix}wheel_FL_joint" type="continuous">
<origin xyz="-0.15256 -0.08214 -0.08802" rpy="0 0 0"/>
<parent link="${link_prefix}rocker_L_link"/>
<child link="${link_prefix}wheel_FL_link"/>
<axis xyz="0 -1 0"/>
<limit effort="2.0" velocity="6.0"/>
<dynamics friction="0.3125" damping="0.1"/>
</joint>
<joint name="${joint_prefix}wheel_RL_joint" type="continuous">
<origin xyz="0.15256 -0.08214 -0.08802" rpy="0 0 0"/>
<parent link="${link_prefix}rocker_L_link"/>
<child link="${link_prefix}wheel_RL_link"/>
<axis xyz="0 -1 0"/>
<limit effort="2.0" velocity="6.0"/>
<dynamics friction="0.3125" damping="0.1"/>
</joint>
<joint name="${joint_prefix}wheel_FR_joint" type="continuous">
<origin xyz="0.15256 -0.08214 -0.08802" rpy="0 0 0"/>
<parent link="${link_prefix}rocker_R_link"/>
<child link="${link_prefix}wheel_FR_link"/>
<axis xyz="0 1 0"/>
<limit effort="2.0" velocity="6.0"/>
<dynamics friction="0.3125" damping="0.1"/>
</joint>
<joint name="${joint_prefix}wheel_RR_joint" type="continuous">
<origin xyz="-0.15256 -0.08214 -0.08802" rpy="0 0 0"/>
<parent link="${link_prefix}rocker_R_link"/>
<child link="${link_prefix}wheel_RR_link"/>
<axis xyz="0 1 0"/>
<limit effort="2.0" velocity="6.0"/>
<dynamics friction="0.3125" damping="0.1"/>
</joint>
<xacro:if value="${default_antenna}">
<joint name="${joint_prefix}antenna_joint" type="fixed">
<origin xyz="-0.0052 0.056 -0.0065" rpy="0 0 0"/>
<parent link="${link_prefix}base_link"/>
<child link="${link_prefix}antenna_link"/>
</joint>
</xacro:if>
<joint name="${joint_prefix}camera_joint" type="fixed">
<origin xyz="0.0971 0 -0.0427" rpy="0 0.2094 0"/>
<parent link="${link_prefix}base_link"/>
<child link="${link_prefix}camera_frame"/>
</joint>
<joint name="${joint_prefix}camera_optical_joint" type="fixed">
<origin xyz="0 0 0" rpy="-${pi/2} 0.0 -${pi/2}"/>
<parent link="${link_prefix}camera_frame"/>
<child link="${link_prefix}camera_optical_frame"/>
</joint>
<joint name="${joint_prefix}imu_joint" type="fixed">
<origin xyz="${imu_translation}" rpy="0 0 0"/>
<parent link="${link_prefix}base_link"/>
<child link="${link_prefix}imu_frame"/>
</joint>
<!-- LEO GAZEBO -->
<xacro:macro name="leo_gazebo"
params="robot_ns:=''">
<xacro:property name="link_prefix" value=""/>
<xacro:if value="${robot_ns != '' and robot_ns != '/'}">
<xacro:property name="link_prefix" value="${robot_ns}/"/>
</xacro:if>
<!-- base ODE properties -->
<gazebo reference="${link_prefix}base_footprint">
<kp>1e6</kp>
<kd>1.0</kd>
<mu1>0.3</mu1>
<mu2>0.3</mu2>
<minDepth>0.003</minDepth>
</gazebo>
<gazebo reference="${link_prefix}base_link">
<kp>1e6</kp>
<kd>1.0</kd>
<mu1>0.3</mu1>
<mu2>0.3</mu2>
<minDepth>0.003</minDepth>
</gazebo>
<!-- rocker ODE properties -->
<gazebo reference="${link_prefix}rocker_L_link">
<kp>1e6</kp>
<kd>1.0</kd>
<mu1>0.3</mu1>
<mu2>0.3</mu2>
<minDepth>0.003</minDepth>
</gazebo>
<gazebo reference="${link_prefix}rocker_R_link">
<kp>1e6</kp>
<kd>1.0</kd>
<mu1>0.3</mu1>
<mu2>0.3</mu2>
<minDepth>0.003</minDepth>
</gazebo>
<!-- wheel ODE properties -->
<gazebo reference="${link_prefix}wheel_FL_link">
<kp>1e6</kp>
<kd>100.0</kd>
<mu1>3.0</mu1>
<mu2>1.0</mu2>
<fdir1>1 0 0</fdir1>
<minDepth>0.003</minDepth>
</gazebo>
<gazebo reference="${link_prefix}wheel_FR_link">
<kp>1e6</kp>
<kd>100.0</kd>
<mu1>3.0</mu1>
<mu2>1.0</mu2>
<fdir1>1 0 0</fdir1>
<minDepth>0.003</minDepth>
</gazebo>
<gazebo reference="${link_prefix}wheel_RL_link">
<kp>1e6</kp>
<kd>100.0</kd>
<mu1>3.0</mu1>
<mu2>1.0</mu2>
<fdir1>1 0 0</fdir1>
<minDepth>0.003</minDepth>
</gazebo>
<gazebo reference="${link_prefix}wheel_RR_link">
<kp>1e6</kp>
<kd>100.0</kd>
<mu1>3.0</mu1>
<mu2>1.0</mu2>
<fdir1>1 0 0</fdir1>
<minDepth>0.003</minDepth>
</gazebo>
<!-- camera -->
<gazebo reference="${link_prefix}camera_frame">
<sensor type="camera" name="camera">
<always_on>true</always_on>
<update_rate>30.0</update_rate>
<visualize>false</visualize>
<camera name="leo_camera">
<horizontal_fov>1.9</horizontal_fov>
<image>
<width>640</width>
<height>480</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.02</near>
<far>300</far>
</clip>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.007</stddev>
</noise>
<distortion>
<k1>-0.279817</k1>
<k2>0.060321</k2>
<k3>0.000487</k3>
<p1>0.000310</p1>
<p2>0.000000</p2>
<center>0.5 0.5</center>
</distortion>
</camera>
<plugin name="camera_controller" filename="libgazebo_ros_camera.so">
<ros><namespace>${robot_ns}</namespace></ros>
<frame_name>camera_optical_frame</frame_name>
</plugin>
</sensor>
</gazebo>
<!-- rocker differential -->
<gazebo>
<plugin name="rocker_differential" filename="libleo_gazebo_differential_plugin.so">
<jointA>rocker_L_joint</jointA>
<jointB>rocker_R_joint</jointB>
<forceConstant>100.0</forceConstant>
</plugin>
</gazebo>
<gazebo reference="${link_prefix}imu_frame">
<sensor type="imu" name="leo_imu_sensor">
<update_rate>100</update_rate>
<plugin filename="libgazebo_ros_imu_sensor.so" name="imu_plugin">
<robotNamespace>${robot_ns}</robotNamespace>
<topicName>imu/data_raw</topicName>
<frameName>${link_prefix}imu_frame</frameName>
<updateRateHZ>100.0</updateRateHZ>
<gaussianNoise>0.01</gaussianNoise>
<initialOrientationAsReference>false</initialOrientationAsReference>
</plugin>
</sensor>
</gazebo>
<ros2_control name="GazeboSystem" type="system">
<hardware>
<plugin>gazebo_ros2_control/GazeboSystem</plugin>
</hardware>
<joint name="rocker_L_joint">
<state_interface name="position"/>
</joint>
<joint name="rocker_R_joint">
<state_interface name="position"/>
</joint>
<joint name="wheel_FL_joint">
<command_interface name="velocity">
<param name="min">-6</param>
<param name="max">6</param>
</command_interface>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="wheel_RL_joint">
<command_interface name="velocity">
<param name="min">-6</param>
<param name="max">6</param>
</command_interface>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="wheel_FR_joint">
<command_interface name="velocity">
<param name="min">-6</param>
<param name="max">6</param>
</command_interface>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="wheel_RR_joint">
<command_interface name="velocity">
<param name="min">-6</param>
<param name="max">6</param>
</command_interface>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
</ros2_control>
<gazebo>
<plugin filename="libgazebo_ros2_control.so" name="gazebo_ros2_control">
<robot_param>robot_description</robot_param>
<robot_param_node>robot_state_publisher</robot_param_node>
<parameters>package://leo_description/config/controllers.yaml</parameters>
</plugin>
</gazebo>
</xacro:macro>
<xacro:macro name="leo_sim"
params="default_antenna:=true
fixed:=false
robot_ns:=''">
<xacro:property name="link_prefix" value=""/>
<xacro:if value="${robot_ns != '' and robot_ns != '/'}">
<xacro:property name="link_prefix" value="${robot_ns}/"/>
</xacro:if>
<xacro:leo default_antenna="${default_antenna}"
rockers_fixed="false"
link_prefix="${link_prefix}"/>
<xacro:leo_gazebo robot_ns="${robot_ns}"/>
<xacro:if value="${fixed}">
<link name="world"/>
<joint name="fixed" type="fixed">
<parent link="world"/>
<child link="${link_prefix}base_footprint"/>
<origin xyz="0.0 0.0 1.0"/>
</joint>
</xacro:if>
</xacro:macro>
</robot>
Asked by RodBelaFarin on 2023-03-09 07:08:41 UTC
Answers
Have you found a solution to this issue? Because I'm currently facing the same problem
Asked by NicolasDubois0 on 2023-04-21 09:52:48 UTC
Comments
Same, I tried using my package on humble instead of foxy and started this error, now my robots wont spawn in gazebo
Asked by i1Cps on 2023-06-14 22:08:21 UTC
Hey, did you find any solution to this?
Asked by suche on 2023-06-16 08:59:38 UTC
Comments
Can you please, upload your leo_sim.urdf.xacro file also.
Thanks for posting the question over here.
Asked by Ranjit Kathiriya on 2023-03-09 07:13:10 UTC
Thanks for following up :)
See my edit 1.
Asked by RodBelaFarin on 2023-03-09 07:31:23 UTC
Can you upload the full package to GitHub and share the link?
Thanks
Asked by Ranjit Kathiriya on 2023-03-10 02:41:18 UTC
Sure. Well... It's not GitHub, but this should work.
I currently don't have access to the sources of the description, but you can install them using
Asked by RodBelaFarin on 2023-03-10 05:19:48 UTC
package 'leo_description' not found
Can you add this also
Asked by Ranjit Kathiriya on 2023-03-10 05:30:29 UTC
weird. It is working for me.
But here you go:
Asked by RodBelaFarin on 2023-03-10 05:39:28 UTC
I am launching
ros2 launch leo_gazebo leo_gazebo.launch.py
btwAsked by RodBelaFarin on 2023-03-10 05:42:20 UTC