diff --git a/odrive_demo_bringup/config/diffbot_controllers.yaml b/odrive_demo_bringup/config/diffbot_controllers.yaml new file mode 100644 index 0000000..cb636c9 --- /dev/null +++ b/odrive_demo_bringup/config/diffbot_controllers.yaml @@ -0,0 +1,57 @@ +controller_manager: + ros__parameters: + update_rate: 100 # Hz + + joint_state_broadcaster: + type: joint_state_broadcaster/JointStateBroadcaster + + diffbot_base_controller: + type: diff_drive_controller/DiffDriveController + +diffbot_base_controller: + ros__parameters: + left_wheel_names: ["left_wheel_joint"] + right_wheel_names: ["right_wheel_joint"] + + wheel_separation: 0.10 + #wheels_per_side: 1 # actually 2, but both are controlled by 1 signal + wheel_radius: 0.015 + + wheel_separation_multiplier: 1.0 + left_wheel_radius_multiplier: 1.0 + right_wheel_radius_multiplier: 1.0 + + publish_rate: 100.0 + odom_frame_id: odom + base_frame_id: base_link + pose_covariance_diagonal : [0.001, 0.001, 0.001, 0.001, 0.001, 0.01] + twist_covariance_diagonal: [0.001, 0.001, 0.001, 0.001, 0.001, 0.01] + + open_loop: false + enable_odom_tf: true + + cmd_vel_timeout: 0.5 + #publish_limited_velocity: true + use_stamped_vel: false + #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 diff --git a/odrive_demo_bringup/launch/odrive.launch.py b/odrive_demo_bringup/launch/odrive.launch.py index b766a16..7b5ffac 100644 --- a/odrive_demo_bringup/launch/odrive.launch.py +++ b/odrive_demo_bringup/launch/odrive.launch.py @@ -102,7 +102,7 @@ def generate_launch_description(): joint_state_broadcaster_spawner = Node( package="controller_manager", executable="spawner", - arguments=["joint_state_broadcaster", "--controller-manager", "/controller_manager"], + arguments=["joint_state_broadcaster", "-c", "/controller_manager"], ) joint0_controller_spawner = Node( diff --git a/odrive_demo_bringup/launch/odrive_diffbot.launch.py b/odrive_demo_bringup/launch/odrive_diffbot.launch.py new file mode 100644 index 0000000..f39c89f --- /dev/null +++ b/odrive_demo_bringup/launch/odrive_diffbot.launch.py @@ -0,0 +1,92 @@ +# Copyright 2022 Factor Robotics +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +from launch import LaunchDescription +from launch.substitutions import Command, FindExecutable, PathJoinSubstitution +from launch_ros.actions import Node +from launch_ros.substitutions import FindPackageShare + + +def generate_launch_description(): + robot_description_content = Command( + [ + PathJoinSubstitution([FindExecutable(name="xacro")]), + " ", + PathJoinSubstitution( + [ + FindPackageShare("odrive_demo_description"), + "urdf", + "odrive_diffbot.urdf.xacro" + ] + ), + ] + ) + robot_description = {"robot_description": robot_description_content} + + robot_controllers = PathJoinSubstitution( + [ + FindPackageShare("odrive_demo_bringup"), + "config", + "diffbot_controllers.yaml", + ] + ) + + rviz_config_file = PathJoinSubstitution( + [ + FindPackageShare("diffbot_description"), + "config", + "diffbot.rviz" + ] + ) + + control_node = Node( + package="controller_manager", + executable="ros2_control_node", + parameters=[robot_description, robot_controllers], + output="both", + ) + + robot_state_pub_node = Node( + package="robot_state_publisher", + executable="robot_state_publisher", + output="both", + parameters=[robot_description], + ) + + joint_state_broadcaster_spawner = Node( + package="controller_manager", + executable="spawner", + arguments=["joint_state_broadcaster", "-c", "/controller_manager"], + ) + + robot_controller_spawner = Node( + package="controller_manager", + executable="spawner", + arguments=["diffbot_base_controller", "-c", "/controller_manager"], + ) + + rviz_node = Node( + package="rviz2", + executable="rviz2", + name="rviz2", + arguments=["-d", rviz_config_file], + ) + + return LaunchDescription([ + control_node, + robot_state_pub_node, + joint_state_broadcaster_spawner, + robot_controller_spawner, + rviz_node + ]) diff --git a/odrive_demo_description/package.xml b/odrive_demo_description/package.xml index 5282b2e..d11e212 100644 --- a/odrive_demo_description/package.xml +++ b/odrive_demo_description/package.xml @@ -9,6 +9,8 @@ ament_cmake_auto + ros2_control_demo_description + ament_cmake diff --git a/odrive_demo_description/urdf/odrive.ros2_control.xacro b/odrive_demo_description/urdf/odrive.ros2_control.xacro index 3f00e8b..e3007e3 100644 --- a/odrive_demo_description/urdf/odrive.ros2_control.xacro +++ b/odrive_demo_description/urdf/odrive.ros2_control.xacro @@ -1,7 +1,8 @@ - + @@ -9,12 +10,12 @@ - 000000000000 + ${serial_number} - - 000000000000 + + ${serial_number} 0 1 0.1 @@ -22,8 +23,8 @@ - - 000000000000 + + ${serial_number} 1 1 0.1 diff --git a/odrive_demo_description/urdf/odrive_diffbot.urdf.xacro b/odrive_demo_description/urdf/odrive_diffbot.urdf.xacro new file mode 100644 index 0000000..6877f20 --- /dev/null +++ b/odrive_demo_description/urdf/odrive_diffbot.urdf.xacro @@ -0,0 +1,19 @@ + + + + + + + + + + + + + + + +