Simple ros2-controll mock setup

This commit is contained in:
2024-09-25 01:43:15 +02:00
commit 98108f9e70
6 changed files with 200 additions and 0 deletions

View File

@ -0,0 +1,70 @@
<?xml version="1.0"?>
<robot name="mg-robot">
<material name="red">
<color rgba="1 0 0 1" />
</material>
<material name="gray">
<color rgba="0.5 0.5 0.5 1" />
</material>
<link name="base-link">
<visual>
<geometry>
<box size="0.5 0.5 0.2" color="yellow"/>
</geometry>
<origin xyz="0 0 0.12" rpy="0 0 0" />
<material name="red" />
</visual>
</link>
<link name="left-wheel">
<visual>
<geometry>
<cylinder radius="0.1" length="0.05"/>
</geometry>
<origin xyz="0 0 0" rpy="1.57 0 0" />
<material name="gray" />
</visual>
</link>
<link name="right-wheel">
<visual>
<geometry>
<cylinder radius="0.1" length="0.05"/>
</geometry>
<origin xyz="0 0 0" rpy="1.57 0 0" />
<material name="gray" />
</visual>
</link>
<joint name="right_motor" type="continuous">
<parent link="base-link"/>
<child link="right-wheel"/>
<origin xyz="0 -0.25 0.1" rpy="0 0 3.141592" />
</joint>
<joint name="left_motor" type="continuous">
<parent link="base-link"/>
<child link="left-wheel"/>
<origin xyz="0 0.25 0.1" rpy="0 0 0" />
</joint>
<ros2_control name="mg-base" type="system">
<hardware>
<plugin>mock_components/GenericSystem</plugin>
<param name="calculate_dynamics">true</param>
</hardware>
<joint name="left_motor">
<command_interface name="velocity"/>
<state_interface name="position"/>
</joint>
<joint name="right_motor">
<command_interface name="velocity"/>
<state_interface name="position"/>
</joint>
</ros2_control>
</robot>

View File

@ -0,0 +1,20 @@
controller_manager:
ros__parameters:
update_rate: 100
diffdrive_controller:
type: diff_drive_controller/DiffDriveController
joint_state_publisher:
type: joint_state_broadcaster/JointStateBroadcaster
diffdrive_controller:
ros__parameters:
left_wheel_names: ["left_motor"]
right_wheel_names: ["right_motor"]
enable_odom_tf: true
odom_frame_id: odom
base_frame_id: base-link
wheel_separation: 0.5
wheel_radius: 0.1