Skip to content

Commit

Permalink
add working demo diff drive
Browse files Browse the repository at this point in the history
  • Loading branch information
harleylara committed Feb 16, 2025
1 parent ffc455e commit f527455
Show file tree
Hide file tree
Showing 5 changed files with 92 additions and 25 deletions.
53 changes: 53 additions & 0 deletions foxy_bringup/config/controllers.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -4,3 +4,56 @@

joint_state_broadcaster:
type: joint_state_broadcaster/JointStateBroadcaster

diff_drive_base_controller:
type: diff_drive_controller/DiffDriveController

/**/diff_drive_base_controller:
ros__parameters:
left_wheel_names: ["left_wheel_joint"]
right_wheel_names: ["right_wheel_joint"]

wheel_separation: 0.45
#wheels_per_side: 1 # actually 2, but both are controlled by 1 signal
wheel_radius: 0.05

wheel_separation_multiplier: 1.0
left_wheel_radius_multiplier: 1.0
right_wheel_radius_multiplier: 1.0

publish_rate: 50.0
odom_frame_id: odom
base_frame_id: base_link
pose_covariance_diagonal : [0.001, 0.001, 0.0, 0.0, 0.0, 0.01]
twist_covariance_diagonal: [0.001, 0.0, 0.0, 0.0, 0.0, 0.01]


open_loop: false
enable_odom_tf: true

cmd_vel_timeout: 0.5
#publish_limited_velocity: true
use_stamped_vel: true
#velocity_rolling_window_size: 10

# Velocity and acceleration limits

# Whenever a min_* is unspecified, default to -max_*
linear.x.has_velocity_limits: true
linear.x.has_acceleration_limits: true
linear.x.has_jerk_limits: false
linear.x.max_velocity: 1.0
linear.x.min_velocity: -1.0
linear.x.max_acceleration: 1.0
linear.x.max_jerk: 0.0
linear.x.min_jerk: 0.0

angular.z.has_velocity_limits: true
angular.z.has_acceleration_limits: true
angular.z.has_jerk_limits: false
angular.z.max_velocity: 1.0
angular.z.min_velocity: -1.0
angular.z.max_acceleration: 1.0
angular.z.min_acceleration: -1.0
angular.z.max_jerk: 0.0
angular.z.min_jerk: 0.0
16 changes: 10 additions & 6 deletions foxy_bringup/config/default.rviz
Original file line number Diff line number Diff line change
Expand Up @@ -75,7 +75,7 @@ Visualization Manager:
Show Axes: false
Show Trail: false
Value: true
foxy_base_link:
foxy/base_link:
Alpha: 1
Show Axes: false
Show Trail: false
Expand Down Expand Up @@ -107,7 +107,9 @@ Visualization Manager:
Value: true
caster_wheel:
Value: true
foxy_base_link:
foxy/base_link:
Value: true
foxy/odom:
Value: true
left_wheel:
Value: true
Expand All @@ -119,7 +121,7 @@ Visualization Manager:
Show Axes: true
Show Names: false
Tree:
foxy_base_link:
foxy/base_link:
base_footprint:
{}
caster_wheel:
Expand All @@ -128,12 +130,14 @@ Visualization Manager:
{}
right_wheel:
{}
foxy/odom:
{}
Update Interval: 0
Value: true
Enabled: true
Global Options:
Background Color: 48; 48; 48
Fixed Frame: foxy_base_link
Fixed Frame: foxy/odom
Frame Rate: 30
Name: root
Tools:
Expand Down Expand Up @@ -212,5 +216,5 @@ Window Geometry:
Views:
collapsed: false
Width: 1349
X: 368
Y: 66
X: 304
Y: 2
21 changes: 12 additions & 9 deletions foxy_bringup/launch/robot.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -11,15 +11,8 @@ def launch_args(context) -> list[LaunchDescriptionEntity]:

declared_args = []

declared_args.append(DeclareLaunchArgument(
"use_sim",
default_value="true",
description="Clock source."
))

declared_args.append(DeclareLaunchArgument(
"robot_name",
default_value="foxy",
description="Robot name."
))

Expand Down Expand Up @@ -74,7 +67,8 @@ def launch_setup(context) -> list[LaunchDescriptionEntity]:
Node(
package="controller_manager",
executable="spawner",
arguments=["joint_state_broadcaster"],
arguments=["joint_state_broadcaster", "diff_drive_base_controller"],
output='screen'
),
]
)
Expand All @@ -101,12 +95,20 @@ def launch_setup(context) -> list[LaunchDescriptionEntity]:
"-x", "0",
"-y", "0",
"-z", "0.3"
]
],
output='screen'
),
],
condition=LaunchConfigurationEquals("system", "gz")
)

bridge = Node(
package='ros_gz_bridge',
executable='parameter_bridge',
arguments=['/clock@rosgraph_msgs/msg/Clock[ignition.msgs.Clock'],
output='screen'
)

rviz2 = Node(
package='rviz2',
executable='rviz2',
Expand All @@ -121,6 +123,7 @@ def launch_setup(context) -> list[LaunchDescriptionEntity]:
robot_state_publisher_node,
controllers,
gz,
bridge,
rviz2
]

Expand Down
21 changes: 14 additions & 7 deletions foxy_description/urdf/base.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -18,13 +18,14 @@

<link name="${root_frame}">
<visual>
<origin xyz="0 0 0.1" rpy="0 0 0" />
<geometry>
<box size="0.6 0.4 0.2" />
</geometry>
<origin xyz="0 0 0.1" rpy="0 0 0" />
<material name="green" />
</visual>
<collision>
<origin xyz="0 0 0.1" rpy="0 0 0" />
<geometry>
<box size="0.6 0.4 0.2" />
</geometry>
Expand All @@ -39,37 +40,41 @@

<link name="left_wheel">
<visual>
<origin xyz="0 0 0" rpy="1.57 0 0" />
<geometry>
<cylinder radius="0.1" length="0.05" />
</geometry>
<origin xyz="0 0 0" rpy="1.57 0 0" />
<material name="grey" />
</visual>
<collision>
<origin xyz="0 0 0" rpy="1.57 0 0" />
<geometry>
<cylinder radius="0.1" length="0.05" />
</geometry>
</collision>
<inertial>
<origin xyz="0 0 0" rpy="1.57 0 0" />
<mass value="1"/>
<inertia ixx="0.4" ixy="0.0" ixz="0.0" iyy="0.4" iyz="0.0" izz="0.2"/>
</inertial>
</link>

<link name="right_wheel">
<visual>
<origin xyz="0 0 0" rpy="1.57 0 0" />
<geometry>
<cylinder radius="0.1" length="0.05" />
</geometry>
<origin xyz="0 0 0" rpy="1.57 0 0" />
<material name="grey" />
</visual>
<collision>
<origin xyz="0 0 0" rpy="1.57 0 0" />
<geometry>
<cylinder radius="0.1" length="0.05" />
</geometry>
</collision>
<inertial>
<origin xyz="0 0 0" rpy="1.57 0 0" />
<mass value="1"/>
<inertia ixx="0.4" ixy="0.0" ixz="0.0" iyy="0.4" iyz="0.0" izz="0.2"/>
</inertial>
Expand All @@ -94,18 +99,20 @@
</inertial>
</link>

<joint name="base_left_wheel_joint" type="continuous">
<joint name="left_wheel_joint" type="continuous">
<parent link="${root_frame}" />
<child link="left_wheel" />
<origin xyz="-0.15 0.225 0" rpy="0 0 0" />
<origin xyz="-0.15 0.25 0" rpy="0 0 0" />
<axis xyz="0 1 0"/>
<dynamics damping="0.2"/>
</joint>

<joint name="base_right_wheel_joint" type="continuous">
<joint name="right_wheel_joint" type="continuous">
<parent link="${root_frame}" />
<child link="right_wheel" />
<origin xyz="-0.15 -0.225 0" rpy="0 0 0" />
<origin xyz="-0.15 -0.25 0" rpy="0 0 0" />
<axis xyz="0 1 0"/>
<dynamics damping="0.2"/>
</joint>

<joint name="base_caster_wheel_joint" type="fixed">
Expand Down
6 changes: 3 additions & 3 deletions foxy_description/urdf/foxy.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@

<!-- set of properties for internal use (not used by launch) -->
<xacro:property name="namespace" default="$(arg robot_name)"/>
<xacro:property name="root_frame" default="${namespace}_base_link" />
<xacro:property name="root_frame" default="${namespace}/base_link" />
<xacro:property name="ros2_gz_before_renamed" value="${['humble', 'galatic', 'foxy']}"/>

<xacro:include filename="$(find foxy_description)/urdf/base.xacro"/>
Expand All @@ -20,15 +20,15 @@
<hardware>
<plugin>ign_ros2_control/IgnitionSystem</plugin>
</hardware>
<joint name="base_left_wheel_joint">
<joint name="left_wheel_joint">
<command_interface name="velocity">
<param name="min">-1</param>
<param name="max">1</param>
</command_interface>
<state_interface name="position"/>
<state_interface name="velocity"/>
</joint>
<joint name="base_right_wheel_joint">
<joint name="right_wheel_joint">
<command_interface name="velocity">
<param name="min">-1</param>
<param name="max">1</param>
Expand Down

0 comments on commit f527455

Please sign in to comment.