fishbot学习

一、构建urdf文件

在urdf中构建一个base_link和imu_link,通过imu_joint确定二者位置关系。在构建身体部分,显示link代表一个大部件,link下可以分visual,表示机器人外观,主要包括原点origin几何形状geometry、材质material

<?xml version="1.0"?>
<robot name="first_robot">
    <!-- 机器人身体部分 -->
    <link name="base_link">
        <!-- 部件外观描述 -->
        <visual>
            <!-- 沿自己几何中心的偏移与旋转量 -->
            <origin xyz="0 0 0" rpy="0 0 0" />
            <!-- 几何形状 -->
            <geometry>
                <!-- 圆柱体,半径0.1m,高度 0.12m -->
                <cylinder length="0.12" radius="0.10" />
            </geometry>
            <!-- 材质子标签-蓝色 -->
            <material name="blue">
                <color rgba="0.1 0.1 1.0 0.5" />
            </material>
        </visual>
    </link>

    <!-- 机器人IMU部件,惯性测量单元传感器 -->
    <link name="imu_link">
        <visual>
            <origin xyz="0 0 0" rpy="0 0 0" />
            <geometry>
                <box size="0.02 0.02 0.02" />
            </geometry>
        </visual>
        <material name="black">
            <color rgba="0 0 0 0.5" />
        </material>
    </link>

    <!-- 机器人关节,用于组合机器人的部件 -->
    <joint name="imu_joint" type="fixed">
        <!-- 父部件 -->
        <parent link="base_link" />
        <!-- 子部件 -->
        <child link="imu_link" />
        <!-- 子部件相对父部件的平移和旋转 -->
        <origin xyz="0 0 0.03" rpy="0 0 0" />
    </joint>

</robot>

二、运行rviz2

通过add添加robotmodel,此时会报两个错,没有base_link与map的位置关系,没有imu_link与map的位置关系,将fixed Frame改为base_link第一个错误解决,第二个错误仍存在,在步骤一中存在base_link与imu_link的位置关系,但rviz不能识别

三、安装依赖

通过安装robot_state_publisher和joint_state_publisher将urdf文件转化为话题并将部件之间的位姿关系通过TF发布出来

sudo apt install ros-$ROS_DIETRO-robot-state-publisher
sudo apt install ros-$ROS_DIETRO-joint-state-publisher

四、创建launch文件夹,同时运行多个节点

import launch
import launch_ros
from ament_index_python.packages import get_package_share_directory


def generate_launch_description():
    # 获取默认路径
    urdf_tutorial_path = get_package_share_directory('fishbot_description')
    default_model_path = urdf_tutorial_path + '/urdf/first_robot.urdf'
    default_rviz_config_path = urdf_tutorial_path + '/config/rviz/display_model.rviz'
    # 为 Launch 声明参数
    action_declare_arg_mode_path = launch.actions.DeclareLaunchArgument(
        name='model', default_value=str(default_model_path),
        description='URDF 的绝对路径')
    # 获取文件内容生成新的参数
    robot_description = launch_ros.parameter_descriptions.ParameterValue(
        launch.substitutions.Command(
            ['xacro ', launch.substitutions.LaunchConfiguration('model')]),
        value_type=str)
    # 状态发布节点
    robot_state_publisher_node = launch_ros.actions.Node(
        package='robot_state_publisher',
        executable='robot_state_publisher',
        parameters=[{'robot_description': robot_description}]
    )
    # 关节状态发布节点
    joint_state_publisher_node = launch_ros.actions.Node(
        package='joint_state_publisher',
        executable='joint_state_publisher',
    )
    # RViz 节点
    rviz_node = launch_ros.actions.Node(
        package='rviz2',
        executable='rviz2',
        arguments=['-d', default_rviz_config_path]
    )
    return launch.LaunchDescription([
        action_declare_arg_mode_path,
        joint_state_publisher_node,
        robot_state_publisher_node,
        rviz_node
    ])

五、运行

在ws文件夹下进行colcon 和source

colcon build
source install/setup.bash
ros2 launch fishbot_description display_robot.launch.py

评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值