차이

문서의 선택한 두 판 사이의 차이를 보여줍니다.

차이 보기로 링크

양쪽 이전 판 이전 판
다음 판
이전 판
activity:public:2020:ros:210216 [2021/02/17 16:56:07] – [1.3.] gakscoriora1activity:public:2020:ros:210216 [2021/02/17 19:58:32] (현재) david
줄 6: 줄 6:
  
 =====1. ===== =====1. =====
 +<sxh>
  
 +</sxh>
  
 ====1.1. ==== ====1.1. ====
줄 14: 줄 16:
 ====1.2. ==== ====1.2. ====
  
-====1.3. ====+====1.3. urdf 파일 만들기 및 실행 ====
  
 +=== urdf 파일 만들기 ===
 +<sxh bash>
 +cd ~/catkin_ws/src
 +catkin_create_pkg testbot_description urdf
 +cd testbot_description
 +mkdir urdf
 +cd urdf
 +gedit testbot.urdf
 +</sxh>
  
  
 +**urdf **
  
 +<sxh xml title:testbot.urdf>
  
 +<?xml version="1.0" ?>
 +<robot name="testbot">
  
 +  <material name="black">
 +    <color rgba="0.0 0.0 0.0 1.0"/>
 +  </material>
 +  <material name="orange">
 +    <color rgba="1.0 0.4 0.0 1.0"/>
 +  </material>
  
-<sxh>sudo apt-get install ros-melodic-ros-controllers ros-melodic-gazebo* ros-melodic-moveit* ros-melodic-industrial-core</sxh>+  <link name="base"/>
  
-<sxh>+  <joint name="fixed" type="fixed"> 
 +    <parent link="base"/> 
 +    <child link="link1"/> 
 +  </joint> 
 + 
 +  <link name="link1"> 
 +    <collision> 
 +      <origin xyz="0 0 0.25" rpy="0 0 0"/> 
 +      <geometry> 
 +        <box size="0.1 0.1 0.5"/> 
 +      </geometry> 
 +    </collision> 
 +    <visual> 
 +      <origin xyz="0 0 0.25" rpy="0 0 0"/> 
 +      <geometry> 
 +        <box size="0.1 0.1 0.5"/> 
 +      </geometry> 
 +      <material name="black"/> 
 +    </visual> 
 +    <inertial> 
 +      <origin xyz="0 0 0.25" rpy="0 0 0"/> 
 +      <mass value="1"/> 
 +      <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/> 
 +    </inertial> 
 +  </link> 
 + 
 +  <joint name="joint1" type="revolute"> 
 +    <parent link="link1"/> 
 +    <child link="link2"/> 
 +    <origin xyz="0 0 0.5" rpy="0 0 0"/> 
 +    <axis xyz="0 0 1"/> 
 +    <limit effort="30" lower="-2.617" upper="2.617" velocity="1.571"/> 
 +  </joint> 
 + 
 +  <link name="link2"> 
 +    <collision> 
 +      <origin xyz="0 0 0.25" rpy="0 0 0"/> 
 +      <geometry> 
 +        <box size="0.1 0.1 0.5"/> 
 +      </geometry> 
 +    </collision> 
 +    <visual> 
 +      <origin xyz="0 0 0.25" rpy="0 0 0"/> 
 +      <geometry> 
 +        <box size="0.1 0.1 0.5"/> 
 +      </geometry> 
 +      <material name="orange"/> 
 +    </visual> 
 +    <inertial> 
 +      <origin xyz="0 0 0.25" rpy="0 0 0"/> 
 +      <mass value="1"/> 
 +      <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/> 
 +    </inertial> 
 +  </link> 
 + 
 +  <joint name="joint2" type="revolute"> 
 +    <parent link="link2"/> 
 +    <child link="link3"/> 
 +    <origin xyz="0 0 0.5" rpy="0 0 0"/> 
 +    <axis xyz="0 1 0"/> 
 +    <limit effort="30" lower="-2.617" upper="2.617" velocity="1.571"/> 
 +  </joint> 
 + 
 +  <link name="link3"> 
 +    <collision> 
 +      <origin xyz="0 0 0.5" rpy="0 0 0"/> 
 +      <geometry> 
 +        <box size="0.1 0.1 1"/> 
 +      </geometry> 
 +    </collision> 
 +    <visual> 
 +      <origin xyz="0 0 0.5" rpy="0 0 0"/> 
 +      <geometry> 
 +        <box size="0.1 0.1 1"/> 
 +      </geometry> 
 +      <material name="black"/> 
 +    </visual> 
 +    <inertial> 
 +      <origin xyz="0 0 0.5" rpy="0 0 0"/> 
 +      <mass value="1"/> 
 +      <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/> 
 +    </inertial> 
 +  </link> 
 + 
 +  <joint name="joint3" type="revolute"> 
 +    <parent link="link3"/> 
 +    <child link="link4"/> 
 +    <origin xyz="0 0 1.0" rpy="0 0 0"/> 
 +    <axis xyz="0 1 0"/> 
 +    <limit effort="30" lower="-2.617" upper="2.617" velocity="1.571"/> 
 +  </joint> 
 + 
 +  <link name="link4"> 
 +    <collision> 
 +      <origin xyz="0 0 0.25" rpy="0 0 0"/> 
 +      <geometry> 
 +        <box size="0.1 0.1 0.5"/> 
 +      </geometry> 
 +    </collision> 
 +    <visual> 
 +      <origin xyz="0 0 0.25" rpy="0 0 0"/> 
 +      <geometry> 
 +        <box size="0.1 0.1 0.5"/> 
 +      </geometry> 
 +      <material name="orange"/> 
 +    </visual> 
 +    <inertial> 
 +      <origin xyz="0 0 0.25" rpy="0 0 0"/> 
 +      <mass value="1"/> 
 +      <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/> 
 +    </inertial> 
 +  </link> 
 + 
 +</robot> 
 + 
 + 
 +</sxh> 
 +==========================================================================================================================\\ 
 +문법검사 
 +<sxh bash title:문법검사> 
 +check_urdf testbot.urdf 
 +</sxh> 
 + 
 +그래프 표시 
 +<sxh bash title:그래프 표시> 
 +urdf_to_graphiz testbot.urdf 
 +</sxh> 
 + 
 +==========================================================================================================================\\ 
 + 
 +\\ 
 +\\ 
 +\\ 
 +\\ 
 + 
 +\\ 
 +\\ 
 +\\ 
 +런치파일 생성 
 +<sxh bash title 런치파일 생성> 
 +cd ~/catkin_ws/src/testbot_description 
 +mkdir launch 
 +cd launch 
 +gedit testbot.launch 
 +</sxh> 
 + 
 + 
 + 
 + 
 + 
 + 
 +launch  
 +<sxh xml title:testbot.launch> 
 +<launch> 
 +  <arg name="model" default="$(find testbot_description)/urdf/testbot.urdf" /> 
 +  <arg name="gui" default="True" /> 
 +  <param name="robot_description" textfile="$(arg model)" /> 
 +  <param name="use_gui" value="$(arg gui)"/> 
 +  <node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher" /> 
 +  <node name="robot_state_publisher" pkg="robot_state_publisher" type="state_publisher" /> 
 +</launch> 
 +</sxh> 
 + 
 + 
 + 
 +<sxh bash> 
 +roslaunch testbot_description testbot.launch 
 +rviz 
 +</sxh> 
 + 
 + 
 + 
 +<sxh bash title:패키지 설치> 
 +sudo apt-get install ros-melodic-ros-controllers ros-melodic-gazebo* ros-melodic-moveit* ros-melodic-industrial-core 
 +</sxh> 
 + 
 +<sxh bash>
 cd ~/catkin_ws/src cd ~/catkin_ws/src
 git clone https://github.com/ROBOTIS-GIT/DynamixelSDK.git git clone https://github.com/ROBOTIS-GIT/DynamixelSDK.git
 git clone https://github.com/ROBOTIS-GIT/dynamixel-workbench.git git clone https://github.com/ROBOTIS-GIT/dynamixel-workbench.git
- git clone https://github.com/ROBOTIS-GIT/dynamixel-workbench-msgs.git+git clone https://github.com/ROBOTIS-GIT/dynamixel-workbench-msgs.git
 git clone https://github.com/ROBOTIS-GIT/open_manipulator.git git clone https://github.com/ROBOTIS-GIT/open_manipulator.git
 git clone https://github.com/ROBOTIS-GIT/open_manipulator_msgs.git git clone https://github.com/ROBOTIS-GIT/open_manipulator_msgs.git
줄 39: 줄 236:
  
  
-<sxh>+ 
 +<sxh bash>
 roslaunch open_manipulator_description open_manipulator_rviz.launch roslaunch open_manipulator_description open_manipulator_rviz.launch
 roslaunch open_manipulator_gazebo open_manipulator_gazebo.launch roslaunch open_manipulator_gazebo open_manipulator_gazebo.launch
 </sxh> </sxh>
 +조인트 2번째 포지션 변경
 +rostopic pub /open_manipulator_chain/joint2_position/command std_msgs/Float64 "data: 1.0" --once
  
  
-<sxh>+<sxh bash>
 roslaunch open_manipulator_description open_manipulator_rviz.launch roslaunch open_manipulator_description open_manipulator_rviz.launch
 roslaunch open_manipulator_control_gui open_manipulator_control_gui.launch roslaunch open_manipulator_control_gui open_manipulator_control_gui.launch
 </sxh> </sxh>
 +
 +
 +
 +
  • activity/public/2020/ros/210216.1613548567.txt.gz
  • 마지막으로 수정됨: 4년 전
  • 저자 gakscoriora1