Animate joints - modulabs/gazebo-tutorial GitHub Wiki
Overview
์ด๋ฒ ์ฅ์์๋ ROS topic์ธ trajectory_msgs::JointTrajectory message ๋ฅผ ์ด์ฉํ์ฌ dynamics ์์ด ์๋ฎฌ๋ ์ด์ ์ผ๋ก ๋ก๋ด์ ์์ง์ผ ์ ์๋ ๋ฐฉ๋ฒ์ ๋ํด์ ์์ ๋ณธ๋ค.
์๋์ ๊ฐ์ด ROS ํจํค์ง๋ฅผ ์์ฑํ๋ค.
cd ~/catkin_ws/src
catkin_create_pkg joint_animation_tutorial rospy trajectory_msgs std_msgs
cd joint_animation_tutorial
mkdir scripts
cd scripts
Model Plugin Controller
joint trajectory model plugin์ด DRC robot์ ๋ด์ฅ๋์ด ์๊ณ ์ด ํ๋ฌ๊ทธ์ธ์ด JointTrajectory messages๋ฅผ ํฌํจํ๋ ROS ํ ํฝ์ ๋ฐ๋๋ค. ๊ทธ๋ฆฌ๊ณ ๋ก๋ด์ ์กฐ์ธํธ๋ฅผ trajectory์ ๋ฐ๋ผ ์์ง์ด๊ฒ ๋๋ค. ์ด๊ฒ์ ๋ก๋ด ๋ชจ๋ธ์ dynamics๋ฅผ ๊ณ ๋ คํ์ง ์๊ณ ๋ก๋ด์ ์์ง์ฌ ๋ณด๊ณ ์ ํ ๋ ์ ์ฉํ๋ค. ์ด ํ๋ฌ๊ทธ์ธ์ ๋ํ ๋ก๋ด์ ์กฐ์ธํธ trajectory๋ฅผ ๊ตฌ๋ํ๋ ๋์ ๋ฌผ๋ฆฌ์ ์ธ ์ ๋ฐ์ดํธ๋ฅผ ํ์ง ์๊ฒ ํ๋ค.
Create a ROS Publisher
ํ์ฌ์ ํด๋์ joint trajectory messages joint_animation.py๋ฅผ ํผ๋ธ๋ฆฌ์ ํ๋ ํ์ด์ฌ์ ROS ๋
ธ๋๋ฅผ ๋ค์ด๋ก๋ ํ๋ค.
wget http://bitbucket.org/osrf/gazebo_tutorials/raw/default/drcsim_animate_joints/files/joint_animation.py
#!/usr/bin/env python
import roslib; roslib.load_manifest('joint_animation_tutorial')
import rospy, math, time
from trajectory_msgs.msg import JointTrajectory, JointTrajectoryPoint
def jointTrajectoryCommand():
# Initialize the node
rospy.init_node('joint_control')
print rospy.get_rostime().to_sec()
while rospy.get_rostime().to_sec() == 0.0:
time.sleep(0.1)
print rospy.get_rostime().to_sec()
pub = rospy.Publisher('/joint_trajectory', JointTrajectory, queue_size=10)
jt = JointTrajectory()
jt.header.stamp = rospy.Time.now()
jt.header.frame_id = "atlas::pelvis"
jt.joint_names.append("atlas::back_lbz" )
jt.joint_names.append("atlas::back_mby" )
jt.joint_names.append("atlas::back_ubx" )
jt.joint_names.append("atlas::neck_ay" )
jt.joint_names.append("atlas::l_leg_uhz")
jt.joint_names.append("atlas::l_leg_mhx")
jt.joint_names.append("atlas::l_leg_lhy")
jt.joint_names.append("atlas::l_leg_kny")
jt.joint_names.append("atlas::l_leg_uay")
jt.joint_names.append("atlas::l_leg_lax")
jt.joint_names.append("atlas::r_leg_lax")
jt.joint_names.append("atlas::r_leg_uay")
jt.joint_names.append("atlas::r_leg_kny")
jt.joint_names.append("atlas::r_leg_lhy")
jt.joint_names.append("atlas::r_leg_mhx")
jt.joint_names.append("atlas::r_leg_uhz")
jt.joint_names.append("atlas::l_arm_elx")
jt.joint_names.append("atlas::l_arm_ely")
jt.joint_names.append("atlas::l_arm_mwx")
jt.joint_names.append("atlas::l_arm_shx")
jt.joint_names.append("atlas::l_arm_usy")
jt.joint_names.append("atlas::l_arm_uwy")
jt.joint_names.append("atlas::r_arm_elx")
jt.joint_names.append("atlas::r_arm_ely")
jt.joint_names.append("atlas::r_arm_mwx")
jt.joint_names.append("atlas::r_arm_shx")
jt.joint_names.append("atlas::r_arm_usy")
jt.joint_names.append("atlas::r_arm_uwy")
n = 1500
dt = 0.01
rps = 0.05
for i in range (n):
p = JointTrajectoryPoint()
theta = rps*2.0*math.pi*i*dt
x1 = -0.5*math.sin(2*theta)
x2 = 0.5*math.sin(1*theta)
p.positions.append(x1)
p.positions.append(x2)
p.positions.append(x2)
p.positions.append(x2)
p.positions.append(x2)
p.positions.append(x2)
p.positions.append(x1)
p.positions.append(x2)
p.positions.append(x1)
p.positions.append(x1)
p.positions.append(x2)
p.positions.append(x1)
p.positions.append(x2)
p.positions.append(x1)
p.positions.append(x1)
p.positions.append(x2)
p.positions.append(x2)
p.positions.append(x1)
p.positions.append(x1)
p.positions.append(x1)
p.positions.append(x2)
p.positions.append(x2)
p.positions.append(x2)
p.positions.append(x1)
p.positions.append(x1)
p.positions.append(x2)
p.positions.append(x1)
p.positions.append(x1)
jt.points.append(p)
# set duration
jt.points[i].time_from_start = rospy.Duration.from_sec(dt)
rospy.loginfo("test: angles[%d][%f, %f]",n,x1,x2)
pub.publish(jt)
rospy.spin()
if __name__ == '__main__':
try:
jointTrajectoryCommand()
except rospy.ROSInterruptException: pass
ํ์ผ์ด ์คํ ๋ ์ ์๋๋ก ์๋์ ๊ฐ์ด ํ์ผ ๊ถํ์ ๋ฐ๊พผ๋ค.
chmod +x joint_animation.py
The Code explained
#!/usr/bin/env python
import roslib; roslib.load_manifest('joint_animation_tutorial')
์ด๊ฒ์ roslib์ ๋ถ๋ฌ์ค๊ณ ์ด ํจํค์ง์ ํฌํจ๋ manifest.xml์ ๋ก๋ํ๋ค.
import rospy, math, time
from trajectory_msgs.msg import JointTrajectory, JointTrajectoryPoint
๋ ๋ง์ ๋ชจ๋์ ๋ถ๋ฌ์ค๊ณ JointTrajectory, JointTrajectoryPoint์ ๋ํ ๋ฉ์์ง ํ์ผ์ ๋ถ๋ฌ์จ๋ค.
Import more modules, and import the message file for JointTrajectory and JointTrajectoryPoint.
def jointTrajectoryCommand():
# Initialize the node
rospy.init_node('joint_control')
print rospy.get_rostime().to_sec()
while rospy.get_rostime().to_sec() == 0.0:
time.sleep(0.1)
print rospy.get_rostime().to_sec()
pub = rospy.Publisher('/joint_trajectory', JointTrajectory, queue_size=10)
์ด๊ฒ์ ๋ ธ๋๋ฅผ ์ด๊ธฐํ ํ๊ณ joint_trajectory ํ ํฝ ํผ๋ธ๋ฆฌ์ ๋ฅผ ์์ฑํ๋ค.
jt = JointTrajectory()
jt.header.stamp = rospy.Time.now()
jt.header.frame_id = "atlas::pelvis"
JointTrajectory ๋ฉ์์ง์ ๊ฐ์ฒด๋ฅผ ์์ฑํ๊ณ ํค๋์ time stamp์ frame_id๋ฅผ ์ถ๊ฐํ๋ค.
jt.joint_names.append("atlas::back_lbz" )
jt.joint_names.append("atlas::back_mby" )
jt.joint_names.append("atlas::back_ubx" )
jt.joint_names.append("atlas::neck_ay" )
jt.joint_names.append("atlas::l_leg_uhz")
jt.joint_names.append("atlas::l_leg_mhx")
jt.joint_names.append("atlas::l_leg_lhy")
jt.joint_names.append("atlas::l_leg_kny")
jt.joint_names.append("atlas::l_leg_uay")
jt.joint_names.append("atlas::l_leg_lax")
jt.joint_names.append("atlas::r_leg_lax")
jt.joint_names.append("atlas::r_leg_uay")
jt.joint_names.append("atlas::r_leg_kny")
jt.joint_names.append("atlas::r_leg_lhy")
jt.joint_names.append("atlas::r_leg_mhx")
jt.joint_names.append("atlas::r_leg_uhz")
jt.joint_names.append("atlas::l_arm_elx")
jt.joint_names.append("atlas::l_arm_ely")
jt.joint_names.append("atlas::l_arm_mwx")
jt.joint_names.append("atlas::l_arm_shx")
jt.joint_names.append("atlas::l_arm_usy")
jt.joint_names.append("atlas::l_arm_uwy")
jt.joint_names.append("atlas::r_arm_elx")
jt.joint_names.append("atlas::r_arm_ely")
jt.joint_names.append("atlas::r_arm_mwx")
jt.joint_names.append("atlas::r_arm_shx")
jt.joint_names.append("atlas::r_arm_usy")
jt.joint_names.append("atlas::r_arm_uwy")
์ปจํธ๋กค ๋ joint ์ด๋ฆ์ ๋ฆฌ์คํธ๋ฅผ ์์ฑํ๋ค.
n = 1500
dt = 0.01
rps = 0.05
for i in range (n):
p = JointTrajectoryPoint()
theta = rps*2.0*math.pi*i*dt
x1 = -0.5*math.sin(2*theta)
x2 = 0.5*math.sin(1*theta)
n=1500์ผ๋ก ์ํ๋๋๋ก ๋ฃจํ๋ฅผ ์ ์ ํ๊ณ ์ด ๋ฃจํ๋ x1, x2์ ์กฐ์ธํธ ๊ฐ๋๋ฅผ ๊ณ์ฐํ๋ค. ์๋์ ์ถ๊ฐ๋ ๊ฐ ์กฐ์ธํธ์ ์์น๊ฐ ๋ ๊ฒ์ด๋ค.
p.positions.append(x1)
p.positions.append(x2)
p.positions.append(x2)
p.positions.append(x2)
p.positions.append(x2)
p.positions.append(x2)
p.positions.append(x1)
p.positions.append(x2)
p.positions.append(x1)
p.positions.append(x1)
p.positions.append(x2)
p.positions.append(x1)
p.positions.append(x2)
p.positions.append(x1)
p.positions.append(x1)
p.positions.append(x2)
p.positions.append(x2)
p.positions.append(x1)
p.positions.append(x1)
p.positions.append(x1)
p.positions.append(x2)
p.positions.append(x2)
p.positions.append(x2)
p.positions.append(x1)
p.positions.append(x1)
p.positions.append(x2)
p.positions.append(x1)
p.positions.append(x1)
jt.points.append(p)
JointTrajectoryPoint๊ฐ ๋ฐ๋ผ๊ฐ ์์น์ ๋ฆฌ์คํธ๋ฅผ ์์ฑํ๋ค. ๊ทธ๋ฆฌ๊ณ JointTrajectoryPoint๋ฅผ JointTrajectory์ ์ถ๊ฐํ๋ค. ๊ทธ๋ฆฌ๊ณ ๋ค์ ํฌ์ธํธ๋ฅผ ์งํํ๋ค.
# set duration
jt.points[i].time_from_start = rospy.Duration.from_sec(dt)
rospy.loginfo("test: angles[%d][%f, %f]",n,x1,x2)
์์ฑ๋ ํฌ์ธํธ๋ฅผ ๋ก๊ทธ๋ก ๋จ๊ธด๋ค.
pub.publish(jt)
rospy.spin()
์ด๊ฒ์ ๋ก๋ด์ ์์ง์ผ ํ๋์ JointTrajectory ๋ฉ์์ง๋ฅผ ํผ๋ธ๋ฆฌ์ ํ ๊ฒ์ด๋ค. ์ด ๋ ธ๋๋ ๊ณ์ํด์ ๋ฐ๋ณต ์ํ๋๋ค.
if __name__ == '__main__':
try:
jointTrajectoryCommand()
except rospy.ROSInterruptException: pass
rospy ๋ ธ๋์ ๋ฉ์ธ ํจ์์ด๊ณ ๋ง์ฝ ์ฐ๋ ๋๊ฐ ๋ค์ด๋๋ฉด ์คํ ์ฝ๋๋ก ๋ถํฐ ๋ ธ๋๋ฅผ ๋ณดํธํ๋ค.
Running the Simulation
-
ํฐ๋ฏธ๋ ์ฐฝ์์ DRC ๋ก๋ด ์๋ฎฌ๋ ์ด์ ์ ์์ํ๋ค.
VRC_CHEATS_ENABLED=1 roslaunch drcsim_gazebo atlas.launch -
๋ก๋ด์ด ๋์ด์ง๋ ๊ฒ์ ๋ฐฉ์ง ํ๊ธฐ ์ํด(์ด๋ค ์ ์ด๊ธฐ๋ค๋ ์๋๋์ง ์๊ณ ์๋ค)
World->Physics->gravity->z์ ํด๋ฆญํ๊ณ ๊ฐ์0.0์ผ๋ก ์ ํ ํด์ ์ค๋ ฅ์ ์์ค๋ค. ํน์ ๋ค์์ ๋ช ๋ น์ด๋ฅผ ์ํํ๋ค.gz physics -g 0,0,0 -
๋ก๋ด์ด ์ง๋ฉด์์ ํ๊ธฐ๊ฑฐ๋ ํ๋์ ๋ ์๋ ๊ฒ์ ๋ฐฉ์งํ๊ธฐ ์ํด(์ค๋ ฅ์ด ์๋ค)
World->Models์ ํด๋ฆญํ๊ณground_plane์ ์ค๋ฅธ์ชฝ ํด๋ฆญํด์ ์ญ์ ๋ฅผ ํด๋ฆญํ๋ค. -
์ค๋ ฅ์ ์์ ๊ณ ground plane์ ์ญ์ ํ๋ค.
Edit->Reset World์ ํด๋ฆญํด์ world๋ฅผ ๋ฆฌ์ ํ๋ค. ๋ก๋ด์ ์ด์ ํ์ ํด๊ณ ์์ ์์ ์์๋ ์ด๊ธฐ ์์ธ๊ฐ ๋ ๊ฒ์ด๋ค. -
๋ค๋ฅธ ํฐ๋ฏธ๋ ์ฐฝ์ ์ด๊ณ ์๋๋ฅผ ์ํํ๋ค.
rosrun joint_animation_tutorial joint_animation.pyDRC ๋ก๋ด์ ํผ๋ธ๋ฆฌ์๋ ROS JointTrajectory ๋ฉ์์ง์ ๋ฐ๋ผ ์์ง์ผ ๊ฒ์ด๋ค.
Atlas v4, v5
์ด ์ํ์ฝ๋๋ Atlas v4์ v5์์๋ ์๋๋์ง ์๋๋ค. ์๋ํ๋ฉด ์ด ๋ชจ๋ธ๋ค์ ๋ค๋ฅธ ์กฐ์ธํธ์ ์ด๋ฆ๊ณผ ๋ ๋ง์ ์กฐ์ธํธ๋ค์ ๊ฐ์ง๊ณ ์๊ธฐ ๋๋ฌธ์ด๋ค. Atlas v4, v5 ์กฐ์ธํธ๋ค์ ์์ง์ด๊ธฐ ์ํด์๋ modified version๋ฅผ ๋ค์ด ๋ฐ์์ผ ํ๋ค. ์ด ์์ ๋ ์ฝ๋๋ ์ ๋ฐ์ดํธ ๋ ์กฐ์ธํธ์ ์ด๋ฆ์ ํฌํจํ๋ค.
jt.joint_names.append("atlas::back_bkz" )
jt.joint_names.append("atlas::back_bky" )
jt.joint_names.append("atlas::back_bkx" )
jt.joint_names.append("atlas::neck_ry" )
jt.joint_names.append("atlas::l_leg_hpz")
jt.joint_names.append("atlas::l_leg_hpx")
jt.joint_names.append("atlas::l_leg_hpy")
jt.joint_names.append("atlas::l_leg_kny")
jt.joint_names.append("atlas::l_leg_aky")
jt.joint_names.append("atlas::l_leg_akx")
jt.joint_names.append("atlas::r_leg_akx")
jt.joint_names.append("atlas::r_leg_aky")
jt.joint_names.append("atlas::r_leg_kny")
jt.joint_names.append("atlas::r_leg_hpy")
jt.joint_names.append("atlas::r_leg_hpx")
jt.joint_names.append("atlas::r_leg_hpz")
jt.joint_names.append("atlas::l_arm_elx")
jt.joint_names.append("atlas::l_arm_ely")
jt.joint_names.append("atlas::l_arm_shz")
jt.joint_names.append("atlas::l_arm_shx")
jt.joint_names.append("atlas::l_arm_wry")
jt.joint_names.append("atlas::l_arm_wrx")
jt.joint_names.append("atlas::l_arm_wry2")
jt.joint_names.append("atlas::r_arm_elx")
jt.joint_names.append("atlas::r_arm_ely")
jt.joint_names.append("atlas::r_arm_shz")
jt.joint_names.append("atlas::r_arm_shx")
jt.joint_names.append("atlas::r_arm_wry")
jt.joint_names.append("atlas::r_arm_wrx")
jt.joint_names.append("atlas::r_arm_wry2")
ํด๋น ์กฐ์ธํธ ๊ฐ๋๋ค์ ์์ฑํ๋ค.
p.positions.append(x2)
p.positions.append(x2)
p.positions.append(x2)
p.positions.append(x2)
p.positions.append(x2)
p.positions.append(x2)
p.positions.append(x1)
p.positions.append(x1)
p.positions.append(x1)
p.positions.append(x2)
p.positions.append(x1)
p.positions.append(x2)
p.positions.append(x1)
p.positions.append(x1)
p.positions.append(x1)
p.positions.append(x2)
p.positions.append(x2)
p.positions.append(x1)
p.positions.append(x1)
p.positions.append(x1)
p.positions.append(x2)
p.positions.append(x2)
p.positions.append(x2)
p.positions.append(x1)
p.positions.append(x1)
p.positions.append(x2)
p.positions.append(x1)
p.positions.append(x1)
p.positions.append(x1)
p.positions.append(x1)
jt.points.append(p)
Note: Atlas v4/v5์์ joint trajectory control ์ธํฐํ์ด์ค๋ฅผ ๊ฐ์ง๊ธฐ ๋๋ฌธ์ PID ์ปจํธ๋กค์ ๊บผ์ผ ํ๋ค. ๊ฒ๋ค๊ฐ Atlas๋ User ๋ชจ๋๋ก ์ ํ ์ด ๋๋ค.
-
์๋ก์ด joint trajectory ํผ๋ธ๋ฆฌ์ ๋ฅผ ์ํํ๊ธฐ ์ํด, ๋จผ์ ํ๋ ์ ์ฌํ ์ ใ ๋ผ๋ฅด ๋ฐ๋ฅธ๋ค. Atlas v4๋ฅผ launchํ๊ธฐ ์ํด ๋ค์ ๋ช ๋ น์ด๋ฅผ ์ํํ๋ค.
VRC_CHEATS_ENABLED=1 roslaunch drcsim_gazebo atlas.launch model_args:="_v4"Atlas v5๋ฅผ ์คํํ๊ณ ์ ํ๋ค๋ฉด ์๋์ ๋ช ๋ น์ด๋ก ์คํ ๊ฐ๋ฅํ๋ค.
VRC_CHEATS_ENABLED=1 roslaunch drcsim_gazebo atlas.launch model_args:="_v5" -
World->Physics->gravity->z๋ฅผ ํด๋ฆญ ํ์ฌ0.0์ผ๋ก ๊ฐ์ ์ค์ ํ๋ฉด ์ค๋ ฅ์ ์์จ ์ ์๋ค. ์๋๋ฉด ์๋์ ๋ช ๋ น์ด๋ก ์ํ ๊ฐ๋ฅํ๋ค.gz physics -g 0,0,0 -
ground๋ฅผ ์ญ์ ํ๋ค.
World->Models์ ํด๋ฆญํ๊ณground_plane์ค๋ฅธ์ชฝ ํด๋ฆญํ์ฌ ์ญ์ ๋ฅผ ํด๋ฆญํ๋ค.` -
Edit->Reset Model Poses๋ฅผ ํด๋ฆญํ์ฌ ๋ชจ๋ธ์ ์์ธ๋ฅผ ์ด๊ธฐํ ํ๋ค. -
๋ง์ง๋ง์ผ๋ก ๋ค๋ฅธ ํฐ๋ฏธ๋์ฐฝ์์
joint_animation_v4v5.py๋ฅผ ์คํํ๋ค.rosrun joint_animation_tutorial joint_animation_v4v5.py