M2 MacBookでGazeboを使う 2

M2 MacBook AirでGazeboを少しずつ覚えていきます。

前の記事はこちら。

M2 MacBookでGazeboを使う 1

今回やること。

  • 壁と障害物を作成
  • ros2通信をGazeboの通信に変換する、またはその逆の起動script作成
  • 全体的な起動script作成
  • teleop

環境。

  • M2 MacBook Air
  • VMware Fusion
  • Ubuntu Server for ARM
  • ROS2 Humble

my world 作成 6

GazeboでBox(立方体)を配置してSave world asして得られたsdfを参考にして壁を作成しました。
保存したfileにはreal_time_update_rateがあります。なんでやー。

<size>1 1 1</size>と立方体の設定になっているのを<size>10 1 1</size>や<size>1 10 1</size>とすることで壁になります。
poseの値を変更して位置を変えます。
<size>10 1 2</size>などとすれば十分に高い壁になります。

下記の部分を読んでください。一番下に書いています。

  • <model name=’wall_right’>
  • <model name=’wall_top’>
  • <model name=’wall_left’>
  • <model name=’wall_bottom’>
  • <model name=’obstacle_top_right’>
  • <model name=’obstacle_top_left’>
  • <model name=’obstacle_bottom_right’>
  • <model name=’obstacle_bottom_left’>

moving_robot_lidar.sdf (for Gazebo Fortress)

<?xml version="1.0" ?>
<sdf version="1.9">
    <world name="Moving_robot">

        <physics name="1ms" type="ignored">
            <max_step_size>0.001</max_step_size>
            <real_time_factor>1.0</real_time_factor>
        </physics>

        <plugin
            filename="libignition-gazebo-physics-system.so"
            name="ignition::gazebo::systems::Physics">
        </plugin>

        <plugin
            filename="libignition-gazebo-user-commands-system.so"
            name="ignition::gazebo::systems::UserCommands">
        </plugin>

        <plugin
            filename="libignition-gazebo-scene-broadcaster-system.so"
            name="ignition::gazebo::systems::SceneBroadcaster">
        </plugin>

        <plugin
            filename="libignition-gazebo-sensors-system.so"
            name="ignition::gazebo::systems::Sensors">
            <render_engine>ogre2</render_engine>
        </plugin>

        <!--
        <gui fullscreen='false'>
            <plugin name='3D View' filename='MinimalScene'>
                <ignition-gui>
                    <title>3D View</title>
                    <property type='bool' key='showTitleBar'>false</property>
                    <property type='string' key='state'>docked</property>
                </ignition-gui>
                <engine>ogre2</engine>
                <scene>scene</scene>
                <ambient_light>0.4 0.4 0.4</ambient_light>
                <background_color>0.8 0.8 0.8</background_color>
                <camera_pose>-6 0 6 0 0.5 0</camera_pose>
            </plugin>

            <plugin name='Scene Manager' filename='GzSceneManager'>
                <ignition-gui>
                    <property key='resizable' type='bool'>true</property>
                    <property key='width' type='double'>5</property>
                    <property key='height' type='double'>5</property>
                    <property key='state' type='string'>floating</property>
                    <property key='showTitleBar' type='bool'>false</property>
                </ignition-gui>
            </plugin>

            <plugin name='Entity tree' filename='EntityTree'>
                <ignition-gui>
                    <property type='string' key='state'>docked</property>
                </ignition-gui>
            </plugin>

            <plugin name='Visualize Lidar' filename='VisualizeLidar'/>
        </gui>
        -->

        <light type="directional" name="sun">
            <cast_shadows>true</cast_shadows>
            <pose>0 0 10 0 0 0</pose>
            <diffuse>0.8 0.8 0.8 1</diffuse>
            <specular>0.2 0.2 0.2 1</specular>
            <attenuation>
                <range>1000</range>
                <constant>0.9</constant>
                <linear>0.01</linear>
                <quadratic>0.001</quadratic>
            </attenuation>
            <direction>-0.5 0.1 -0.9</direction>
        </light>

        <model name="ground_plane">
            <static>true</static>
            <link name="link">
                <collision name="collision">
                <geometry>
                    <plane>
                    <normal>0 0 1</normal>
                    </plane>
                </geometry>
                </collision>
                <visual name="visual">
                <geometry>
                    <plane>
                    <normal>0 0 1</normal>
                    <size>100 100</size>
                    </plane>
                </geometry>
                <material>
                    <ambient>0.8 0.8 0.8 1</ambient>
                    <diffuse>0.8 0.8 0.8 1</diffuse>
                    <specular>0.8 0.8 0.8 1</specular>
                </material>
                </visual>
            </link>
        </model>

        <model name='vehicle_blue'>
            <pose relative_to='world'>0 0 0 0 0 0</pose>   <!--the pose is relative to the world by default-->

            <link name='chassis'>
                <pose relative_to='__model__'>0.5 0 0.4 0 0 0</pose>
                <inertial> <!--inertial properties of the link mass, inertia matix-->
                    <mass>1.14395</mass>
                    <inertia>
                        <ixx>0.126164</ixx>
                        <ixy>0</ixy>
                        <ixz>0</ixz>
                        <iyy>0.416519</iyy>
                        <iyz>0</iyz>
                        <izz>0.481014</izz>
                    </inertia>
                </inertial>
                <visual name='visual'>
                    <geometry>
                        <box>
                            <size>2.0 1.0 0.5</size> <!--question: this size is in meter-->
                        </box>
                    </geometry>
                    <!--let's add color to our link-->
                    <material>
                        <ambient>0.0 0.0 1.0 1</ambient>
                        <diffuse>0.0 0.0 1.0 1</diffuse>
                        <specular>0.0 0.0 1.0 1</specular>
                    </material>
                </visual>
                <collision name='collision'> <!--todo: describe why we need the collision-->
                    <geometry>
                        <box>
                            <size>2.0 1.0 0.5</size>
                        </box>
                    </geometry>
                </collision>
            </link>

            <link name='lidar_link'>
                <pose>1 0 1 0 0 0</pose>
                <inertial>
                    <mass>0.10000000000000001</mass>
                    <inertia>
                        <ixx>0.00016666700000000001</ixx>
                        <iyy>0.00016666700000000001</iyy>
                        <izz>0.00016666700000000001</izz>
                        <ixy>0</ixy>
                        <ixz>0</ixz>
                        <iyz>0</iyz>
                    </inertia>
                    <pose>0 0 0 0 -0 0</pose>
                </inertial>
                <collision name='collision'>
                    <geometry>
                        <box>
                            <size>0.1 0.1 0.1</size>
                        </box>
                    </geometry>
                    <surface>
                        <friction>
                            <ode/>
                        </friction>
                        <bounce/>
                        <contact/>
                    </surface>
                </collision>
                <visual name='visual'>
                    <geometry>
                        <box>
                            <size>0.1 0.1 0.1</size>
                        </box>
                    </geometry>
                </visual>
                <sensor name='gpu_lidar' type='gpu_lidar'>
                    <pose>0 0 0 0 -0 0</pose>
                    <topic>scan</topic>
                    <update_rate>10</update_rate>
                    <enable_metrics>false</enable_metrics>
                    <lidar>
                        <scan>
                            <horizontal>
                                <samples>640</samples>
                                <resolution>1</resolution>
                                <min_angle>-1.3962600000000001</min_angle>
                                <max_angle>1.3962600000000001</max_angle>
                            </horizontal>
                            <vertical>
                                <samples>1</samples>
                                <min_angle>0</min_angle>
                                <max_angle>0</max_angle>
                                <resolution>1</resolution>
                            </vertical>
                        </scan>
                        <range>
                            <min>0.080000000000000002</min>
                            <max>10</max>
                            <resolution>0.01</resolution>
                        </range>
                        <noise>
                            <type>none</type>
                            <mean>0</mean>
                            <stddev>0</stddev>
                        </noise>
                        <visibility_mask>4294967295</visibility_mask>
                    </lidar>
                </sensor>
                <enable_wind>false</enable_wind>
            </link>

            <!-- <frame name="lidar_frame" attached_to='chassis'> -->
            <!--     <pose>0 0 0.1 0 0 0</pose> -->
            <!-- </frame> -->

            <!--let's build the left wheel-->
            <link name='left_wheel'>
                <pose relative_to="chassis">-0.5 0.6 0 -1.5707 0 0</pose> <!--angles are in radian-->
                <inertial>
                    <mass>2</mass>
                    <inertia>
                        <ixx>0.145833</ixx>
                        <ixy>0</ixy>
                        <ixz>0</ixz>
                        <iyy>0.145833</iyy>
                        <iyz>0</iyz>
                        <izz>0.125</izz>
                    </inertia>
                </inertial>
                <visual name='visual'>
                    <geometry>
                        <cylinder>
                            <radius>0.4</radius>
                            <length>0.2</length>
                        </cylinder>
                    </geometry>
                    <material>
                        <ambient>1.0 0.0 0.0 1</ambient>
                        <diffuse>1.0 0.0 0.0 1</diffuse>
                        <specular>1.0 0.0 0.0 1</specular>
                    </material>
                </visual>
                <collision name='collision'>
                    <geometry>
                        <cylinder>
                            <radius>0.4</radius>
                            <length>0.2</length>
                        </cylinder>
                    </geometry>
                </collision>
            </link>

            <!--copy and paste for right wheel but change position-->
            <link name='right_wheel'>
                <pose relative_to="chassis">-0.5 -0.6 0 -1.5707 0 0</pose> <!--angles are in radian-->
                <inertial>
                    <mass>1</mass>
                    <inertia>
                        <ixx>0.145833</ixx>
                        <ixy>0</ixy>
                        <ixz>0</ixz>
                        <iyy>0.145833</iyy>
                        <iyz>0</iyz>
                        <izz>0.125</izz>
                    </inertia>
                </inertial>
                <visual name='visual'>
                    <geometry>
                        <cylinder>
                            <radius>0.4</radius>
                            <length>0.2</length>
                        </cylinder>
                    </geometry>
                    <material>
                        <ambient>1.0 0.0 0.0 1</ambient>
                        <diffuse>1.0 0.0 0.0 1</diffuse>
                        <specular>1.0 0.0 0.0 1</specular>
                    </material>
                </visual>
                <collision name='collision'>
                    <geometry>
                        <cylinder>
                            <radius>0.4</radius>
                            <length>0.2</length>
                        </cylinder>
                    </geometry>
                </collision>
            </link>

            <frame name="caster_frame" attached_to='chassis'>
                <pose>0.8 0 -0.2 0 0 0</pose>
            </frame>

            <!--caster wheel-->
            <link name='caster'>
                <pose relative_to='caster_frame'/>
                <inertial>
                    <mass>1</mass>
                    <inertia>
                        <ixx>0.1</ixx>
                        <ixy>0</ixy>
                        <ixz>0</ixz>
                        <iyy>0.1</iyy>
                        <iyz>0</iyz>
                        <izz>0.1</izz>
                    </inertia>
                </inertial>
                <visual name='visual'>
                    <geometry>
                        <sphere>
                            <radius>0.2</radius>
                        </sphere>
                    </geometry>
                    <material>
                        <ambient>0.0 1 0.0 1</ambient>
                        <diffuse>0.0 1 0.0 1</diffuse>
                        <specular>0.0 1 0.0 1</specular>
                    </material>
                </visual>
                <collision name='collision'>
                    <geometry>
                        <sphere>
                            <radius>0.2</radius>
                        </sphere>
                    </geometry>
                </collision>
            </link>


            <!--connecting these links together using joints-->
            <joint name='left_wheel_joint' type='revolute'> <!--continous joint is not supported yet-->
                <pose relative_to='left_wheel'/>
                <parent>chassis</parent>
                <child>left_wheel</child>
                <axis>
                    <xyz expressed_in='__model__'>0 1 0</xyz> <!--can be defined as any frame or even arbitrary frames-->
                    <limit>
                        <lower>-1.79769e+308</lower>    <!--negative infinity-->
                        <upper>1.79769e+308</upper>     <!--positive infinity-->
                    </limit>
                </axis>
            </joint>

            <joint name='right_wheel_joint' type='revolute'>
                <pose relative_to='right_wheel'/>
                <parent>chassis</parent>
                <child>right_wheel</child>
                <axis>
                    <xyz expressed_in='__model__'>0 1 0</xyz>
                    <limit>
                        <lower>-1.79769e+308</lower>    <!--negative infinity-->
                        <upper>1.79769e+308</upper>     <!--positive infinity-->
                    </limit>
                </axis>
            </joint>

            <!--different type of joints ball joint--> <!--defult value is the child-->
            <joint name='caster_wheel' type='ball'>
                <parent>chassis</parent>
                <child>caster</child>
            </joint>

            <joint name='lidar_sensor_joint' type='fixed'>
                <parent>chassis</parent>
                <child>lidar_link</child>
                <pose>0 0 0 0 0 0</pose>
            </joint>

            <!--diff drive plugin-->
            <plugin
                filename="libignition-gazebo-diff-drive-system.so"
                name="ignition::gazebo::systems::DiffDrive">
                <left_joint>left_wheel_joint</left_joint>
                <right_joint>right_wheel_joint</right_joint>
                <wheel_separation>1.2</wheel_separation>
                <wheel_radius>0.4</wheel_radius>
                <odom_publish_frequency>1</odom_publish_frequency>
                <topic>cmd_vel</topic>
            </plugin>
        </model>

        <model name='wall_right'>
            <pose>0 -20 0 0 -0 0</pose>
            <link name='box_link'>
                <inertial>
                    <inertia>
                        <ixx>0.16666</ixx>
                        <ixy>0</ixy>
                        <ixz>0</ixz>
                        <iyy>0.16666</iyy>
                        <iyz>0</iyz>
                        <izz>0.16666</izz>
                    </inertia>
                    <mass>1</mass>
                    <pose>0 0 0 0 -0 0</pose>
                </inertial>
                <collision name='box_collision'>
                    <geometry>
                        <box>
                            <size>40 1 2.5</size>
                        </box>
                    </geometry>
                    <surface>
                        <friction>
                            <ode/>
                        </friction>
                        <bounce/>
                        <contact/>
                    </surface>
                </collision>
                <visual name='box_visual'>
                    <geometry>
                        <box>
                            <size>40 1 2.5</size>
                        </box>
                    </geometry>
                    <material>
                        <ambient>0.3 0.3 0.3 1</ambient>
                        <diffuse>0.7 0.7 0.7 1</diffuse>
                        <specular>1 1 1 1</specular>
                    </material>
                </visual>
                <pose>0 0 0 0 -0 0</pose>
                <enable_wind>false</enable_wind>
            </link>
            <static>false</static>
            <self_collide>false</self_collide>
        </model>

        <model name='wall_top'>
            <pose>20 0 0 0 -0 0</pose>
            <link name='box_link'>
                <inertial>
                    <inertia>
                        <ixx>0.16666</ixx>
                        <ixy>0</ixy>
                        <ixz>0</ixz>
                        <iyy>0.16666</iyy>
                        <iyz>0</iyz>
                        <izz>0.16666</izz>
                    </inertia>
                    <mass>1</mass>
                    <pose>0 0 0 0 -0 0</pose>
                </inertial>
                <collision name='box_collision'>
                    <geometry>
                        <box>
                            <size>1 40 2.5</size>
                        </box>
                    </geometry>
                    <surface>
                        <friction>
                            <ode/>
                        </friction>
                        <bounce/>
                        <contact/>
                    </surface>
                </collision>
                <visual name='box_visual'>
                    <geometry>
                        <box>
                            <size>1 40 2.5</size>
                        </box>
                    </geometry>
                    <material>
                        <ambient>0.3 0.3 0.3 1</ambient>
                        <diffuse>0.7 0.7 0.7 1</diffuse>
                        <specular>1 1 1 1</specular>
                    </material>
                </visual>
                <pose>0 0 0 0 -0 0</pose>
                <enable_wind>false</enable_wind>
            </link>
            <static>false</static>
            <self_collide>false</self_collide>
        </model>

        <model name='wall_left'>
            <pose>0 20 0 0 -0 0</pose>
            <link name='box_link'>
                <inertial>
                    <inertia>
                        <ixx>0.16666</ixx>
                        <ixy>0</ixy>
                        <ixz>0</ixz>
                        <iyy>0.16666</iyy>
                        <iyz>0</iyz>
                        <izz>0.16666</izz>
                    </inertia>
                    <mass>1</mass>
                    <pose>0 0 0 0 -0 0</pose>
                </inertial>
                <collision name='box_collision'>
                    <geometry>
                        <box>
                            <size>40 1 2.5</size>
                        </box>
                    </geometry>
                    <surface>
                        <friction>
                            <ode/>
                        </friction>
                        <bounce/>
                        <contact/>
                    </surface>
                </collision>
                <visual name='box_visual'>
                    <geometry>
                        <box>
                            <size>40 1 2.5</size>
                        </box>
                    </geometry>
                    <material>
                        <ambient>0.3 0.3 0.3 1</ambient>
                        <diffuse>0.7 0.7 0.7 1</diffuse>
                        <specular>1 1 1 1</specular>
                    </material>
                </visual>
                <pose>0 0 0 0 -0 0</pose>
                <enable_wind>false</enable_wind>
            </link>
            <static>false</static>
            <self_collide>false</self_collide>
        </model>

        <model name='wall_bottom'>
            <pose>-20 0 0 0 -0 0</pose>
            <link name='box_link'>
                <inertial>
                    <inertia>
                        <ixx>0.16666</ixx>
                        <ixy>0</ixy>
                        <ixz>0</ixz>
                        <iyy>0.16666</iyy>
                        <iyz>0</iyz>
                        <izz>0.16666</izz>
                    </inertia>
                    <mass>1</mass>
                    <pose>0 0 0 0 -0 0</pose>
                </inertial>
                <collision name='box_collision'>
                    <geometry>
                        <box>
                            <size>1 40 2.5</size>
                        </box>
                    </geometry>
                    <surface>
                        <friction>
                            <ode/>
                        </friction>
                        <bounce/>
                        <contact/>
                    </surface>
                </collision>
                <visual name='box_visual'>
                    <geometry>
                        <box>
                            <size>1 40 2.5</size>
                        </box>
                    </geometry>
                    <material>
                        <ambient>0.3 0.3 0.3 1</ambient>
                        <diffuse>0.7 0.7 0.7 1</diffuse>
                        <specular>1 1 1 1</specular>
                    </material>
                </visual>
                <pose>0 0 0 0 -0 0</pose>
                <enable_wind>false</enable_wind>
            </link>
            <static>false</static>
            <self_collide>false</self_collide>
        </model>

        <model name='obstacle_top_right'>
            <pose>9 -9 0 0 0 0</pose>
            <link name='box_link'>
                <inertial>
                    <inertia>
                        <ixx>0.16666</ixx>
                        <ixy>0</ixy>
                        <ixz>0</ixz>
                        <iyy>0.16666</iyy>
                        <iyz>0</iyz>
                        <izz>0.16666</izz>
                    </inertia>
                    <mass>1</mass>
                    <pose>0 0 0 0 -0 0</pose>
                </inertial>
                <collision name='box_collision'>
                    <geometry>
                        <box>
                            <size>2 2 2.5</size>
                        </box>
                    </geometry>
                    <surface>
                        <friction>
                            <ode/>
                        </friction>
                        <bounce/>
                        <contact/>
                    </surface>
                </collision>
                <visual name='box_visual'>
                    <geometry>
                        <box>
                            <size>2 2 2.5</size>
                        </box>
                    </geometry>
                    <material>
                        <ambient>0.3 0.3 0.3 1</ambient>
                        <diffuse>0.7 0.7 0.7 1</diffuse>
                        <specular>1 1 1 1</specular>
                    </material>
                </visual>
                <pose>0 0 0 0 -0 0</pose>
                <enable_wind>false</enable_wind>
            </link>
            <static>false</static>
            <self_collide>false</self_collide>
        </model>

        <model name='obstacle_top_left'>
            <pose>9 9 0 0 0 0</pose>
            <link name='box_link'>
                <inertial>
                    <inertia>
                        <ixx>0.16666</ixx>
                        <ixy>0</ixy>
                        <ixz>0</ixz>
                        <iyy>0.16666</iyy>
                        <iyz>0</iyz>
                        <izz>0.16666</izz>
                    </inertia>
                    <mass>1</mass>
                    <pose>0 0 0 0 -0 0</pose>
                </inertial>
                <collision name='box_collision'>
                    <geometry>
                        <box>
                            <size>2 2 2.5</size>
                        </box>
                    </geometry>
                    <surface>
                        <friction>
                            <ode/>
                        </friction>
                        <bounce/>
                        <contact/>
                    </surface>
                </collision>
                <visual name='box_visual'>
                    <geometry>
                        <box>
                            <size>2 2 2.5</size>
                        </box>
                    </geometry>
                    <material>
                        <ambient>0.3 0.3 0.3 1</ambient>
                        <diffuse>0.7 0.7 0.7 1</diffuse>
                        <specular>1 1 1 1</specular>
                    </material>
                </visual>
                <pose>0 0 0 0 -0 0</pose>
                <enable_wind>false</enable_wind>
            </link>
            <static>false</static>
            <self_collide>false</self_collide>
        </model>

        <model name='obstacle_bottom_right'>
            <pose>-8 -8 0 0 0 0</pose>
            <link name='box_link'>
                <inertial>
                    <inertia>
                        <ixx>0.16666</ixx>
                        <ixy>0</ixy>
                        <ixz>0</ixz>
                        <iyy>0.16666</iyy>
                        <iyz>0</iyz>
                        <izz>0.16666</izz>
                    </inertia>
                    <mass>1</mass>
                    <pose>0 0 0 0 -0 0</pose>
                </inertial>
                <collision name='box_collision'>
                    <geometry>
                        <box>
                            <size>4 4 2.5</size>
                        </box>
                    </geometry>
                    <surface>
                        <friction>
                            <ode/>
                        </friction>
                        <bounce/>
                        <contact/>
                    </surface>
                </collision>
                <visual name='box_visual'>
                    <geometry>
                        <box>
                            <size>4 4 2.5</size>
                        </box>
                    </geometry>
                    <material>
                        <ambient>0.3 0.3 0.3 1</ambient>
                        <diffuse>0.7 0.7 0.7 1</diffuse>
                        <specular>1 1 1 1</specular>
                    </material>
                </visual>
                <pose>0 0 0 0 -0 0</pose>
                <enable_wind>false</enable_wind>
            </link>
            <static>false</static>
            <self_collide>false</self_collide>
        </model>

        <model name='obstacle_bottom_left'>
            <pose>-8 8 0 0 0 0</pose>
            <link name='box_link'>
                <inertial>
                    <inertia>
                        <ixx>0.16666</ixx>
                        <ixy>0</ixy>
                        <ixz>0</ixz>
                        <iyy>0.16666</iyy>
                        <iyz>0</iyz>
                        <izz>0.16666</izz>
                    </inertia>
                    <mass>1</mass>
                    <pose>0 0 0 0 -0 0</pose>
                </inertial>
                <collision name='box_collision'>
                    <geometry>
                        <box>
                            <size>4 4 2.5</size>
                        </box>
                    </geometry>
                    <surface>
                        <friction>
                            <ode/>
                        </friction>
                        <bounce/>
                        <contact/>
                    </surface>
                </collision>
                <visual name='box_visual'>
                    <geometry>
                        <box>
                            <size>4 4 2.5</size>
                        </box>
                    </geometry>
                    <material>
                        <ambient>0.3 0.3 0.3 1</ambient>
                        <diffuse>0.7 0.7 0.7 1</diffuse>
                        <specular>1 1 1 1</specular>
                    </material>
                </visual>
                <pose>0 0 0 0 -0 0</pose>
                <enable_wind>false</enable_wind>
            </link>
            <static>false</static>
            <self_collide>false</self_collide>
        </model>

    </world>
</sdf>

適当に作っておいて、適宜変更する予定です。
壁と障害物をとりあえず配置しました。

前回と同様ですが実行手順を再掲します。


$ cd ~/ros/robot_ws/src/robot_and_world
$ cd worlds
$ ign gazebo moving_robot_sensor.sdf

001

横から見た様子。

002

gui tagがあると基本的な操作が出来なくなりますのでcomment outしてます。
LiDARを描画したいときはcomment outを外します。

boxを短く整理して書く方法とかgui tagありでも基本的な操作が出来る方法があるはずとは思いますがsdf職人になりたいわけではないので放置してます。

my world 作成 7

1つのtopicで1つのbridgeを起動するのは大変なのでyamlを使う方法を使うようにします。


$ ros2 run ros_gz_bridge parameter_bridge --ros-args -p config_file:=bridge.yaml

bridge.yaml

---
- ros_topic_name: "/cmd_vel"
  gz_topic_name: "/cmd_vel"
  ros_type_name: "geometry_msgs/msg/Twist"
  gz_type_name: "gz.msgs.Twist"
  direction: ROS_TO_GZ
- ros_topic_name: "/clock"
  gz_topic_name: "/clock"
  ros_type_name: "rosgraph_msgs/msg/Clock"
  gz_type_name: "gz.msgs.Clock"
  direction: GZ_TO_ROS
- ros_topic_name: "/odometry"
  gz_topic_name: "/odometry"
  ros_type_name: "nav_msgs/msg/Odometry"
  gz_type_name: "gz.msgs.Odometry"
  direction: GZ_TO_ROS
- ros_topic_name: "/scan"
  gz_topic_name: "/scan"
  ros_type_name: "sensor_msgs/msg/LaserScan"
  gz_type_name: "gz.msgs.LaserScan"
  direction: GZ_TO_ROS
- ros_topic_name: "/joint_states"
  gz_topic_name: "/joint_state"
  ros_type_name: "sensor_msgs/msg/JointState"
  gz_type_name: "gz.msgs.Model"
  direction: GZ_TO_ROS
- ros_topic_name: "/tf"
  gz_topic_name: "/model/vehicle_blue/tf"
  ros_type_name: "tf2_msgs/msg/TFMessage"
  gz_type_name: "gz.msgs.Pose_V"
  direction: GZ_TO_ROS
- ros_topic_name: "/tf_static"
  gz_topic_name: "/pose_static"
  ros_type_name: "tf2_msgs/msg/TFMessage"
  gz_type_name: "gz.msgs.Pose_V"
  direction: GZ_TO_ROS

my world 作成 8

上記をshell scriptにします。

run.sh

#! /bin/sh

gnome-terminal --geometry=160x60+550+10 -- bash -c ". /home/jn/.bashrc;
ign gazebo -r moving_robot_sensor.sdf"

gnome-terminal --geometry=160x60+550+10 -- bash -c ". /home/jn/.bashrc;
ros2 run ros_gz_bridge parameter_bridge --ros-args -p config_file:=bridge.yaml"

teleop


$ ros2 run teleop_twist_keyboard teleop_twist_keyboard




«       »