前言:很多小伙伴会问到为什么OriginCar智能机器人转弯时角度很小,导致转弯时没有办法进行大幅度的转弯。
解决办法:在代码中把转弯半径限制打开;
首先找到镜像中该文件 origincar_base/launch/origincar_bringup.launch.py
将一下内容替换掉原有内容即可
import os
from pathlib import Path
import launch
from launch.actions import SetEnvironmentVariable
from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch.actions import (DeclareLaunchArgument, GroupAction,
IncludeLaunchDescription, SetEnvironmentVariable)
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch.substitutions import LaunchConfiguration, PythonExpression
from launch_ros.actions import PushRosNamespace
import launch_ros.actions
from launch.conditions import UnlessCondition
def generate_launch_description():
# Get the launch directory
bringup_dir = get_package_share_directory('origincar_base')
launch_dir = os.path.join(bringup_dir, 'launch')
ekf_config = Path(get_package_share_directory('origincar_base'), 'config', 'ekf.yaml')
imu_config = Path(get_package_share_directory('origincar_base'), 'config', 'imu.yaml')
carto_slam = LaunchConfiguration('carto_slam', default='false')
carto_slam_dec = DeclareLaunchArgument('carto_slam',default_value='false')
origincar_base = IncludeLaunchDescription(
PythonLaunchDescriptionSource(os.path.join(launch_dir, 'base_serial.launch.py')),
launch_arguments={'akmcar': 'false'}.items(),
)
choose_car = IncludeLaunchDescription(
PythonLaunchDescriptionSource(os.path.join(launch_dir, 'robot_mode_description.launch.py')),
)
base_to_link = launch_ros.actions.Node(
package='tf2_ros',
executable='static_transform_publisher',
name='base_to_link',
arguments=['0.41', '0.12', '0','0', '0','0','base_footprint','base_link'],
)
base_to_gyro = launch_ros.actions.Node(
package='tf2_ros',
executable='static_transform_publisher',
name='base_to_gyro',
arguments=['0', '0', '0','0', '0','0','base_footprint','gyro_link'],
)
imu_filter_node = launch_ros.actions.Node(
package='imu_filter_madgwick',
executable='imu_filter_madgwick_node',
parameters=[imu_config]
)
robot_ekf = launch_ros.actions.Node(
condition=UnlessCondition(carto_slam),
package='robot_localization',
executable='ekf_node',
parameters=[ekf_config],
remappings=[("odometry/filtered", "odom_combined")]
)
joint_state_publisher_node = launch_ros.actions.Node(
package='joint_state_publisher',
executable='joint_state_publisher',
name='joint_state_publisher',
)
ld = LaunchDescription()
ld.add_action(carto_slam_dec)
ld.add_action(origincar_base)
ld.add_action(base_to_link)
ld.add_action(base_to_gyro)
ld.add_action(joint_state_publisher_node)
ld.add_action(choose_car)
ld.add_action(imu_filter_node)
ld.add_action(robot_ekf)
return ld
替换结束之后,需要回到dev_ws目录下执行 colcon build 进行编译
第三方账号登入
QQ 微博 微信