Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
31 changes: 16 additions & 15 deletions champ_base/config/velocity_smoother/velocity_smoother.yaml
Original file line number Diff line number Diff line change
@@ -1,22 +1,23 @@
# Example configuration:
# - velocity limits are around a 10% above the physical limits
# - acceleration limits are just low enough to avoid jerking
velocity_smoother:
ros__parameters:
# Mandatory parameters
speed_lim_v_x: 0.5
speed_lim_v_y: 0.35

# Mandatory parameters
speed_lim_v_x: 0.5
speed_lim_v_y: 0.35
speed_lim_w: 0.4

speed_lim_w: 0.4
accel_lim_v: 1.0
accel_lim_w: 2.0

accel_lim_v: 1.0
accel_lim_w: 2.0
# Optional parameters
frequency: 10.0
decel_factor: 1.0

# Optional parameters
frequency: 10.0
decel_factor: 1.0

# Robot velocity feedback type:
# 0 - none
# 1 - odometry
# 2 - end robot commands
robot_feedback: 2
# Robot velocity feedback type:
# 0 - none
# 1 - odometry
# 2 - end robot commands
robot_feedback: 2
14 changes: 14 additions & 0 deletions champ_bringup/launch/bringup.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -139,6 +139,17 @@ def generate_launch_description():
declare_close_loop_odom = DeclareLaunchArgument(
"close_loop_odom", default_value="false", description=""
)

velocity_smoother_ld = IncludeLaunchDescription(
PythonLaunchDescriptionSource(
os.path.join(
get_package_share_directory("champ_bringup"),
"launch",
"include",
"velocity_smoother.launch.py",
)
)
)

description_ld = IncludeLaunchDescription(
PythonLaunchDescriptionSource(
Expand All @@ -154,6 +165,7 @@ def generate_launch_description():
}.items(),
)

# ToDo: publish_joint_states requires conditional arg based on joint_hardware_connected (ROS2 doesn't support such style yet)
quadruped_controller_node = Node(
package="champ_base",
executable="quadruped_controller_node",
Expand All @@ -173,6 +185,7 @@ def generate_launch_description():
remappings=[("/cmd_vel/smooth", "/cmd_vel")],
)

# ToDo: orientation_from_imu requires conditional arg based on joint_hardware_connected (ROS2 doesn't support such style yet)
state_estimator_node = Node(
package="champ_base",
executable="state_estimation_node",
Expand Down Expand Up @@ -255,6 +268,7 @@ def generate_launch_description():
declare_publish_foot_contacts,
declare_publish_odom_tf,
declare_close_loop_odom,
velocity_smoother_ld,
description_ld,
quadruped_controller_node,
state_estimator_node,
Expand Down
36 changes: 36 additions & 0 deletions champ_bringup/launch/include/velocity_smoother.launch.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,36 @@

from os import path

from launch import LaunchDescription
from launch.substitutions import LaunchConfiguration
from ament_index_python.packages import get_package_share_directory
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch.actions import IncludeLaunchDescription


def generate_launch_description():
config_path = path.join(
get_package_share_directory('champ_base'),
'config',
'velocity_smoother',
'velocity_smoother.yaml'
)

velocity_smoother_launch = IncludeLaunchDescription(
PythonLaunchDescriptionSource(
path.join(
get_package_share_directory("yocs_velocity_smoother"),
"launch",
"velocity_smoother.launch.py"
)
),
launch_arguments={
"config_file": LaunchConfiguration("config_file", default=config_path),
"raw_cmd_vel_topic": LaunchConfiguration("raw_cmd_vel_topic", default="cmd_vel"),
"smooth_cmd_vel_topic": LaunchConfiguration("smooth_cmd_vel_topic", default="cmd_vel/smooth"),
"robot_cmd_vel_topic": LaunchConfiguration("robot_cmd_vel_topic", default="cmd_vel"),
"odom_topic": LaunchConfiguration("odom_topic", default="odom")
}.items()
)

return LaunchDescription([velocity_smoother_launch])
2 changes: 1 addition & 1 deletion champ_bringup/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -16,12 +16,12 @@
<exec_depend>champ_base</exec_depend>
<exec_depend>robot_localization</exec_depend>
<exec_depend>joint_state_publisher_gui</exec_depend>
<exec_depend>yocs_velocity_smoother</exec_depend>

<build_export_depend>rclcpp</build_export_depend>
<build_export_depend>pluginlib</build_export_depend>
<build_export_depend>geometry_msgs</build_export_depend>
<build_export_depend>nav_msgs</build_export_depend>
<build_export_depend>ecl_threads</build_export_depend>

<export>
<build_type>ament_cmake</build_type>
Expand Down