cd catkin_ws/src
catkin_create_pkg mobile_robot
cd mobile_robot
mkdir urdf
cd urdf
gedit body.urdf.xacro
body.urdf.xacro 파일 안에 다음 내용을 넣어준다.
xacro파일은 urdf를 작성할 때 변수지정, 매크로 등을 사용해서 좀 더 쉽고 편하게 작성할 수 있도록 도와주는 파일이다.
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="mobile_robot">
<link name="body">
<visual>
<geometry>
<box size="2 1 0.7"/>
</geometry>
</visual>
<collision>
<geometry>
<box size="2 1 0.7"/>
</geometry>
</collision>
<inertial>
<mass value="4"/>
<inertia ixx="0.4967" ixy="0.0" ixz="0" iyy="1.4967" iyz="0" izz="1.6667"/>
</inertial>
</link>
<!--............................................rf_wheel...................................................... -->
<link name= "rf_wheel">
<visual>
<origin rpy="1.570795 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.2" radius="0.5"/>
</geometry>
</visual>
<collision>
<origin rpy="1.570795 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.2" radius="0.5"/>
</geometry>
</collision>
<inertial>
<origin rpy="1.570795 0 0" xyz="0 0 0"/>
<mass value="1"/>
<inertia ixx="0.06583" ixy="0.0" ixz="0.0" iyy="0.06583" iyz="0.0" izz="0.125"/>
</inertial>
</link>
<joint name="body_rf_wheel" type="continuous">
<axis xyz="0 1 0"/>
<parent link="body"/>
<child link="rf_wheel"/>
<origin rpy="0 0 0" xyz="0.7 -0.6 0"/>
<limit effort="100" velocity="1.0"/>
</joint>
<!--............................................rb_wheel...................................................... -->
<link name= "rb_wheel">
<visual>
<origin rpy="1.570795 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.2" radius="0.5"/>
</geometry>
</visual>
<collision>
<origin rpy="1.570795 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.2" radius="0.5"/>
</geometry>
</collision>
<inertial>
<origin rpy="1.570795 0 0" xyz="0 0 0"/>
<mass value="1"/>
<inertia ixx="0.06583" ixy="0.0" ixz="0.0" iyy="0.06583" iyz="0.0" izz="0.125"/>
</inertial>
</link>
<joint name="body_rb_wheel" type="continuous">
<axis xyz="0 1 0"/>
<parent link="body"/>
<child link="rb_wheel"/>
<origin rpy="0 0 0" xyz="-0.7 -0.6 0"/>
<limit effort="100" velocity="1.0"/>
</joint>
<!--............................................lf_wheel...................................................... -->
<link name= "lf_wheel">
<visual>
<origin rpy="1.570795 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.2" radius="0.5"/>
</geometry>
</visual>
<collision>
<origin rpy="1.570795 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.2" radius="0.5"/>
</geometry>
</collision>
<inertial>
<origin rpy="1.570795 0 0" xyz="0 0 0"/>
<mass value="1"/>
<inertia ixx="0.06583" ixy="0.0" ixz="0.0" iyy="0.06583" iyz="0.0" izz="0.125"/>
</inertial>
</link>
<joint name="body_lf_wheel" type="continuous">
<axis xyz="0 1 0"/>
<parent link="body"/>
<child link="lf_wheel"/>
<origin rpy="0 0 0" xyz="0.7 0.6 0"/>
<limit effort="100" velocity="1.0"/>
</joint>
<!--............................................lb_wheel...................................................... -->
<link name= "lb_wheel">
<visual>
<origin rpy="1.570795 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.2" radius="0.5"/>
</geometry>
</visual>
<collision>
<origin rpy="1.570795 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.2" radius="0.5"/>
</geometry>
</collision>
<inertial>
<origin rpy="1.570795 0 0" xyz="0 0 0"/>
<mass value="1"/>
<inertia ixx="0.06583" ixy="0.0" ixz="0.0" iyy="0.06583" iyz="0.0" izz="0.125"/>
</inertial>
</link>
<joint name="body_lb_wheel" type="continuous">
<axis xyz="0 1 0"/>
<parent link="body"/>
<child link="lb_wheel"/>
<origin rpy="0 0 0" xyz="-0.7 0.6 0"/>
<limit effort="100" velocity="1.0"/>
</joint>
<!--............................................trnasmission...................................................... -->
<transmission name="rf_transmission">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="rf_motor">
<mechanicalReduction>1</mechanicalReduction>
</actuator>
<joint name="body_rf_wheel">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
</joint>
</transmission>
<transmission name="rb_transmission">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="rb_motor">
<mechanicalReduction>1</mechanicalReduction>
</actuator>
<joint name="body_rb_wheel">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
</joint>
</transmission>
<transmission name="lf_transmission">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="lf_motor">
<mechanicalReduction>1</mechanicalReduction>
</actuator>
<joint name="body_lf_wheel">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
</joint>
</transmission>
<transmission name="lb_transmission">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="lb_motor">
<mechanicalReduction>1</mechanicalReduction>
</actuator>
<joint name="body_lb_wheel">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
</joint>
</transmission>
<gazebo>
<plugin name="skid_steer_drive_controller" filename="libgazebo_ros_skid_steer_drive.so">
<updateRate>100.0</updateRate>
<robotNamespace>/</robotNamespace>
<leftFrontJoint>body_lf_wheel</leftFrontJoint>
<rightFrontJoint>body_rf_wheel</rightFrontJoint>
<leftRearJoint>body_lb_wheel</leftRearJoint>
<rightRearJoint>body_rb_wheel</rightRearJoint>
<wheelSeparation>0.2</wheelSeparation>
<wheelDiameter>0.4</wheelDiameter>
<torque>100</torque>
<robotBaseFrame>body</robotBaseFrame>
<topicName>cmd_vel</topicName>
<broadcastTF>false</broadcastTF>
</plugin>
</gazebo>
</robot>
저장하고 끈다.
cd ..
mkdir launch
cd launch
gedit mobile_robot_gazebo.launch
다음 내용을 넣어준다.
<?xml version="1.0"?>
<launch>
<arg name="model" value="$(find mobile_robot)/urdf/body.urdf.xacro"/>
<param name="robot_description" command="$(find xacro)/xacro $(arg model)" />
<include file="$(find gazebo_ros)/launch/empty_world.launch">
<arg name="debug" value="false" />
<arg name="gui" value="true" />
<arg name="paused" value="false"/>
<arg name="use_sim_time" value="true"/>
<arg name="headless" value="false"/>
</include>
<node name="urdf_spawner"
pkg="gazebo_ros"
type="spawn_model"
respawn="false"
output="screen"
args="-z 1.0
-unpause
-urdf
-model robot
-param robot_description"/>
<rosparam command="load" file="$(find mobile_robot)/config/mobile_robot.yaml" />
<node name="bot_controller_spawner"
pkg="controller_manager"
type="spawner"
args="joint_state_controller
right_front_arm_controller
right_back_arm_controller
left_front_arm_controller
left_back_arm_controller"/>
</launch>
저장하고 끈다.
cd ..
mkdir config
cd config
gedit mobile_robot.yaml
다음 내용을 넣어준다.
joint_state_controller:
type: "joint_state_controller/JointStateController"
publish_rate: 50
right_front_arm_controller:
type: "position_controllers/JointPositionController"
joint: body_rf_wheel
right_back_arm_controller:
type: "position_controllers/JJointPositionController"
joint: body_rb_wheel
left_front_arm_controller:
type: "position_controllers/JointPositionController"
joint: body_lf_wheel
left_back_arm_controller:
type: "position_controllers/JointPositionController"
joint: body_lb_wheel
저장하고 끈다.
키보드 제어를 위한 teleop_twist_keyboard 파일을 다운 받는다.
cd
cd catkin_ws/src
git clone https://github.com/methylDragon/teleop_twist_keyboard_cpp.git
빌드 후 roslaunch로 mobile robot을 gazebo상에서 실행시키고 rosrun으로 teleop_twist_keyboard 노드를 실행한다.
cd ..
cd catkin_ws
catkin build
source ~/catkin_ws/devel/setup.bash
roslaunch mobile_robot mobile_robot_gazebo.launch
rosrun teleop_twist_keyboard_cpp teleop_twist_keyboard
'정나우 > ROS' 카테고리의 다른 글
DQN을 활용한 Cartpole 문제 풀기 (0) | 2022.04.12 |
---|---|
[에러 해결] sudo-apt get update가 안 될 때 (1) | 2022.04.10 |
[ROS] Gazebo상에서 joint_position rosservice값으로 로봇 PID제어하기 (0) | 2022.03.05 |
[ROS] Gazebo상에서 rosservice를 이용해서 joint position값 받기 (0) | 2022.02.10 |
ROS URDF로 이동로봇 위에 매니퓰레이터 만들기 + imu센서 달기 (0) | 2022.01.22 |
댓글