gazebo plug in으로 robot move

로봇을 불렀으면, cmd_vel 토픽으로 움직이고 싶다. 찾다보니 gazebo가 제공하는 plugin로 움직일 수 있음을 알았다. 플러그인 설정으로 어느 토픽을 읽어서 모델을 움직일지 결정한다.

https://classic.gazebosim.org/tutorials?tut=ros_gzplugins

gcamp_gazebo 샘플 프로그램을 참조 했다. gazebo로 로봇을 움직이려면 필요한 몇 개 파일을 만들어야 한다.

now0930@amd2004:~/ros_test/workspace/src/wander_bot$ tree
.
├── CMakeLists.txt
├── gazebo_world.launch
├── launch
│   ├── hello.launch
│   ├── my_world.launch
│   └── robot_description.launch
├── log.txt
├── package.xml
├── src
│   └── red_green_light.py
├── urdf
│   ├── robot.gazebo
│   ├── robot.xacro
│   └── test.urdf
└── worlds
    ├── my_world
    └── my_world2

4 directories, 13 files

roslaunch로 launch에 있는 my_world.launch에서 시작한다.

oot@amd2004:/home/ros_test/workspace/src/wander_bot# cat launch/my_world.launch 
<?xml version="1.0" encoding="UTF-8"?>

<launch>
	<!-- Robot pose -->
	<arg name="x" default="0"/>
	<arg name="y" default="0"/>
	<arg name="z" default="0"/>
	<arg name="roll" default="0"/>
	<arg name="pitch" default="0"/>
	<arg name="yaw" default="0"/>
	<arg name="model_name"   default="agv_number1"/>



			<!-- We resume the logic in empty_world.launch, changing only the name of the world to be launched -->
		<include file="$(find gazebo_ros)/launch/empty_world.launch">
			<arg name="world_name" value="$(find wander_bot)/worlds/my_world2"/>
			<arg name="use_sim_time" value="true"/>
				<!-- more default parameters can be changed here -->
		</include>
		<arg name="package_name"  default="wander_bot" />
		<arg name="path"   value="(find $(arg package_name))" />
		<arg name="dollar" value="$" />

		<include file="$(arg dollar)$(arg path)/launch/robot_description.launch"/> 

			<!-- Spawn My Robot -->
			<!--
				<node name="urdf_spawner" pkg="gazebo_ros" type="spawn_model" respawn="false" output="screen" 
				args="-urdf -param robot_description -model $(arg model_name) 
				-x $(arg x) -y $(arg y) -z $(arg z)
				-R $(arg roll) -P $(arg pitch) -Y $(arg yaw)"/>
			-->
				<node name="urdf_spawner" pkg="gazebo_ros" type="spawn_model" respawn="false" output="screen" 
					args="-urdf -param robot_description -model $(arg model_name) 
					-x $(arg x) -y $(arg y) -z $(arg z)
					-R $(arg roll) -P $(arg pitch) -Y $(arg yaw)"/>


				<node name="test_node" pkg="wander_bot" type="red_green_light.py"
					args="/cmd_vel">
			</node>
		</launch>
    <include file="$(arg dollar)$(arg path)/launch/robot_description.launch"/> 

launch가 robot description을 실행하는데, command로 robot.xacro로 세부 설정을 한다. command가 아닌 다른 방식으로는 모델이 움직이지 않는다. robot description 내부에는 robot_description, joint_state_publisher, robot_state_publisher 3개를 설정한다.

now0930@amd2004:~/ros_test/workspace/src/wander_bot$ cat launch/robot_description.launch 
<?xml version="1.0"?>
<launch>

	<!-- send urdf to param server -->
	<!-- xacro -->

	<param name="robot_description" command="$(find xacro)/xacro --inorder '$(find wander_bot)/urdf/robot.xacro'" />

		<!-- urdf or raw xml file -->
		<!-- <param name="robot_description" command="cat $(find museumGuide)/urdf_model/peoplebot.xml" /> -->

			<!-- Send fake joint values-->
		<node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher">
			<param name="use_gui" value="False"/>
		</node>

		<!-- Send robot states to tf -->
		<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" respawn="false" output="screen"/>

	</launch>

robot.xacro를 보면

now0930@amd2004:~/ros_test/workspace/src/wander_bot$ cat urdf/robot.xacro 
<?xml version="1.0" ?>
<robot name="mobile_robot" xmlns:xacro="http://www.ros.org/wiki/xacro">
	<material name="blue">
		<color rgba = "0 0 0.8 1"/>
	</material>

	<material name="gray">
		<color rgba = "1 1 1 1"/>
	</material>

	<material name="blueviolet">
		<color rgba = "0.54 0.16 0.88 1"/>
	</material>

	<link name = "base_footprint"/>

	<xacro:include filename="$(find wander_bot)/urdf/robot.gazebo" />

	<link name="base_link">
		<visual>
			<origin xyz="0 0 0" rpy = "0 0 0"/>
			<geometry>
				<box size = "0.3 0.24 0.1" rpy = "0 0 0" />
			</geometry>
			<material name = "gray"/>

		</visual>
		<collision>
			<origin xyz="0 0 0.03" rpy = "0 0 0"/>
			<geometry>
				<box size = "0.3 0.25 0.1" />
			</geometry>

		</collision>
		<inertial>
			<mass value = "1.0" />
			<inertia  ixx="1.0" ixy="0.0"  ixz="0.0"  iyy="1.0"  iyz="0.0"  izz="1.0" />
		</inertial>

	</link>


	<joint name = "base_footprint_fixed" type = "fixed">
		<origin xyz = "0 0 0.03" rpy = "0 0 0"/>
		<parent link = "base_footprint"/>
		<child link = "base_link"/>
	</joint>


	<link name = "left_wheel">
		<visual>
			<origin xyz = "0 0 0" rpy = "1.570796 0 0" />
			<geometry>
				<cylinder length = "0.05" radius = "0.08" />
			</geometry>
			<material name ="blue"/>

		</visual>
		<collision>
			<origin xyz = "0 0 0" rpy = "1.570796 0 0" />
			<geometry>
				<cylinder length = "0.05" radius = "0.08" />
			</geometry>

		</collision>
		<inertial>
			<mass value = "1.0" />
			<inertia  ixx="1.0" ixy="0.0"  ixz="0.0"  iyy="1.0"  iyz="0.0"  izz="1.0" />
		</inertial>



	</link>

	<link name = "right_wheel">
		<visual>
			<origin xyz = "0 0 0" rpy = "1.570796 0 0" />
			<geometry>
				<cylinder length = "0.05" radius = "0.08" />
			</geometry>
			<material name ="blue"/>

		</visual>
		<collision>
			<origin xyz = "0 0 0" rpy = "1.570796 0 0" />
			<geometry>
				<cylinder length = "0.05" radius = "0.08" />
			</geometry>

		</collision>

		<inertial>
			<mass value = "1.0" />
			<inertia  ixx="1.0" ixy="0.0"  ixz="0.0"  iyy="1.0"  iyz="0.0"  izz="1.0" />
		</inertial>

	</link>


	<joint name = "left_wheel_joint" type = "continuous">
		<origin xyz = "0.1 0.15 0" rpy = "0 0 0"/>
		<parent link = "base_link"/>
		<child link = "left_wheel"/>
		<axis xyz = "0 1 0"/>

	</joint>

	<joint name = "right_wheel_joint" type = "continuous">
		<origin xyz = "0.1 -0.15 0" rpy = "0 0 0"/>
		<parent link = "base_link"/>
		<child link = "right_wheel"/>
		<axis xyz = "0 1 0" />

	</joint>

	<link name="scanner_link">
		<visual>
			<origin xyz="0 0 0" rpy = "0 0 0"/>
			<geometry>
				<cylinder length="0.05" radius="0.035"/>
			</geometry>
			<material name = "blueviolet"/>

		</visual>
		<collision>
			<origin xyz="0 0 0" rpy = "0 0 0"/>
			<geometry>
				<cylinder length="0.05" radius="0.035"/>
			</geometry>

		</collision>
		<inertial>
			<mass value = "1.0" />
			<inertia  ixx="1.0" ixy="0.0"  ixz="0.0"  iyy="10.0"  iyz="0.0"  izz="1.0" />
		</inertial>

	</link>

	<joint name = "head_scanner" type = "fixed">
		<origin xyz = "0.15 0 0" rpy = "0 1.5708 0"/>
		<parent link = "base_link"/>
		<child link = "scanner_link"/>
	</joint>


	<ros>
		<namespace>/</namespace>
		<argument>/cmd_vel:=cmd_vel</argument>
	</ros>

</robot>

여기에 gazebo 파일을 설정해야 한다.

now0930@amd2004:~/ros_test/workspace/src/wander_bot/urdf$ cat robot.gazebo 
<?xml version="1.0"?>
<robot>
	<gazebo>
		<plugin name="differential_drive_controller" filename="libgazebo_ros_diff_drive.so">
			<legacyMode>false</legacyMode>
			<updateRate>10</updateRate>
			<alwaysOn>true</alwaysOn>
			<leftJoint>left_wheel_joint</leftJoint>
			<rightJoint>right_wheel_joint</rightJoint>
			<torque>10</torque>
			<robotBaseFrame>base_footprint</robotBaseFrame>
			<wheelSeparation>0.4</wheelSeparation>
			<wheelDiameter>0.2</wheelDiameter>
			<publishWheelTF>false</publishWheelTF>
			<publishTf>1</publishTf>
			<commandTopic>cmd_vel</commandTopic>
			<odometryTopic>odom</odometryTopic>
			<odometryFrame>odom</odometryFrame>
			<publishWheelJointState>false</publishWheelJointState>
			<rosDebugLevel>na</rosDebugLevel>
			<wheelAcceleration>0</wheelAcceleration>
			<wheelTorque>5</wheelTorque>
			<odometrySource>world</odometrySource>
			<publishOdomTF>true</publishOdomTF>

		</plugin>
	</gazebo>

</robot>

모두 설정하고 roslaunch를 하면, 관성 모멘트가 잘못 되었는지 이상하게 움직인다.

코멘트

댓글 남기기

이 사이트는 Akismet을 사용하여 스팸을 줄입니다. 댓글 데이터가 어떻게 처리되는지 알아보세요.