更多创客作品,请关注笔者网站园丁鸟,搜集全球极具创意,且有价值的创客作品
由于后续要做机械臂的控制,会用到机器人的urdf描述文件,moveit需要根据urdf中的数据进行机械臂的路径规划,这里介绍一下如何一步一步创建机器人的urdf模型描述文件,最终做好的urdf模型如下图
1.首先要注意的是在ros中使用的右手坐标系,所以描述文件中的数据都是以此坐标系为原则
2.先建立baseline的
<?xml version="1.0"?><robot name="diego1">//机器人的名称<link name="base_link">//对应TF坐标体系中的设备frame的名称<visual><geometry><box size="0.20 .15 .003"/>//机器人的base_link的长、宽、高,单位是米</geometry></visual></link></robot>
3.增加底盘两侧的连接件
代码接着上面的添加就可以
<link name="left_leg">//左侧<visual><geometry><box size="0.14 .003 .095"/></geometry></visual></link><joint name="base_to_left_leg" type="fixed">//增加base_link 和left_leg的joint<parent link="base_link"/><child link="left_leg"/><origin xyz="0.0 0.075 -0.046"/>//相对于parent link的位移</joint><link name="right_leg">//右侧<visual><geometry><box size="0.14 .003 .095"/></geometry></visual></link><joint name="base_to_right_leg" type="fixed"><parent link="base_link"/><child link="right_leg"/><origin xyz="0.0 -0.075 -0.046"/>//相对于parent link的位移</joint>
这里可以看到图上的有三个柱子,即对应的坐标系,红x,绿y,蓝z
4.增加前后从动轮的固定装置,由于urdf基本描述文件中没有三角形,这里先暂时用矩形代替,其中参数和前面的是一样的,只要把位移算对了就ok,这里就不做解释,只贴上代码
<link name="left_leg_front">//左侧前端<visual><geometry><box size="0.05 .003 .03"/></geometry></visual></link><joint name="base_to_left_leg_front" type="fixed"><parent link="left_leg"/><child link="left_leg_front"/><origin xyz="0.095 0.0 -0.0025"/></joint><link name="left_leg_back"><visual><geometry><box size="0.05 .003 .03"/></geometry></visual></link><joint name="base_to_left_leg_back" type="fixed"><parent link="left_leg"/><child link="left_leg_back"/><origin xyz="-0.095 0.0 -0.0325"/></joint><link name="right_leg_front"><visual><geometry><box size="0.05 .003 .03"/></geometry></visual></link><joint name="base_to_right_leg_front" type="fixed"><parent link="right_leg"/><child link="right_leg_front"/><origin xyz="0.095 0.0 -0.0025"/></joint><link name="right_leg_back"><visual><geometry><box size="0.05 .003 .03"/></geometry></visual></link><joint name="base_to_right_leg_back" type="fixed"><parent link="right_leg"/><child link="right_leg_back"/><origin xyz="-0.095 0.0 -0.0325"/></joint>
5.增加履带主动轮轴,在urdf中圆柱体默认是平面朝上,需要沿X轴旋转90度
<link name="tyer_master_right_axis"><visual><geometry><cylinder length=".06" radius="0.005"></cylinder></geometry><material name="yellow"><color rgba="1 1 0 1"/></material> </visual></link><joint name="right_leg_to_master_right_axix" type="fixed"><axis xyz="0 0 1"/> <parent link="right_leg"/><child link="tyer_master_right_axis"/><origin rpy="1.57075 0 0" xyz="0.03 -0.0315 0.0175"/>//旋转90度,并相对于right_leg位移相应距离<limit effort="100" velocity="100"/> <joint_properties damping="0.0" friction="0.0"/></joint><link name="tyer_master_left_axis"><visual><geometry><cylinder length=".06" radius="0.005"></cylinder></geometry><material name="yellow"><color rgba="1 1 0 1"/></material> </visual></link><joint name="left_leg_to_master_left_axis" type="fixed"><axis xyz="0 0 1"/> <parent link="left_leg"/><child link="tyer_master_left_axis"/><origin rpy="1.57075 0 0" xyz="0.03 0.0315 0.0175"/>//旋转90度,并相对于left_leg位移相应距离<limit effort="100" velocity="100"/> <joint_properties damping="0.0" friction="0.0"/></joint>
6.增加底部电机马达
<link name="tyer_master_right_motor"><visual><geometry><cylinder length=".068" radius="0.0075"></cylinder></geometry><material name="black"><color rgba="0 0 0 1"/></material> </visual></link><joint name="right_leg_to_master_right_motor" type="fixed"><axis xyz="0 0 1"/> <parent link="right_leg"/><child link="tyer_master_right_motor"/><origin rpy="1.57075 0 0" xyz="0.03 0.0315 0.0175"/><limit effort="100" velocity="100"/> <joint_properties damping="0.0" friction="0.0"/></joint><link name="tyer_master_left_motor"><visual><geometry><cylinder length=".06" radius="0.0075"></cylinder></geometry><material name="black"><color rgba="0 0 0 1"/></material> </visual></link><joint name="left_leg_to_master_left_motor" type="fixed"><axis xyz="0 0 1"/> <parent link="left_leg"/><child link="tyer_master_left_motor"/><origin rpy="1.57075 0 0" xyz="0.03 -0.0315 0.0175"/><limit effort="100" velocity="100"/> <joint_properties damping="0.0" friction="0.0"/></joint>
7.增加从动轮轴
<link name="tyer_slave_right_axis1"><visual><geometry><cylinder length=".06" radius="0.005"></cylinder></geometry><material name="yellow"><color rgba="1 1 0 1"/></material> </visual></link><joint name="right_leg_to_slave_right_axix1" type="continuous"><axis xyz="0 0 1"/> <parent link="right_leg_front"/><child link="tyer_slave_right_axis1"/><origin rpy="1.57075 0 0" xyz="0.02 -0.0315 0.0"/><limit effort="100" velocity="100"/> <joint_properties damping="0.0" friction="0.0"/></joint><link name="tyer_slave_right_axis2"><visual><geometry><cylinder length=".06" radius="0.005"></cylinder></geometry><material name="yellow"><color rgba="1 1 0 1"/></material> </visual></link><joint name="right_leg_to_slave_right_axix2" type="continuous"><axis xyz="0 0 1"/> <parent link="right_leg"/><child link="tyer_slave_right_axis2"/><origin rpy="1.57075 0 0" xyz="0.063 -0.0315 -0.0405"/><limit effort="100" velocity="100"/> <joint_properties damping="0.0" friction="0.0"/></joint><link name="tyer_slave_right_axis3"><visual><geometry><cylinder length=".06" radius="0.005"></cylinder></geometry><material name="yellow"><color rgba="1 1 0 1"/></material> </visual></link><joint name="right_leg_to_slave_right_axix3" type="continuous"><axis xyz="0 0 1"/> <parent link="right_leg"/><child link="tyer_slave_right_axis3"/><origin rpy="1.57075 0 0" xyz="0.008 -0.0315 -0.0405"/><limit effort="100" velocity="100"/> <joint_properties damping="0.0" friction="0.0"/></joint><link name="tyer_slave_right_axis4"><visual><geometry><cylinder length=".06" radius="0.005"></cylinder></geometry><material name="yellow"><color rgba="1 1 0 1"/></material> </visual></link><joint name="right_leg_to_slave_right_axix4" type="continuous"><axis xyz="0 0 1"/> <parent link="right_leg"/><child link="tyer_slave_right_axis4"/><origin rpy="1.57075 0 0" xyz="-0.047 -0.0315 -0.0405"/><limit effort="100" velocity="100"/> <joint_properties damping="0.0" friction="0.0"/></joint> <link name="tyer_slave_right_axis5"><visual><geometry><cylinder length=".06" radius="0.005"></cylinder></geometry><material name="yellow"><color rgba="1 1 0 1"/></material> </visual></link><joint name="right_leg_to_slave_right_axix5" type="continuous"><axis xyz="0 0 1"/> <parent link="right_leg_back"/><child link="tyer_slave_right_axis5"/><origin rpy="1.57075 0 0" xyz="-0.018 -0.0315 -0.008"/><limit effort="100" velocity="100"/> <joint_properties damping="0.0" friction="0.0"/></joint> <link name="tyer_slave_left_axis1"><visual><geometry><cylinder length=".06" radius="0.005"></cylinder></geometry><material name="yellow"><color rgba="1 1 0 1"/></material> </visual></link><joint name="right_leg_to_slave_left_axix1" type="continuous"><axis xyz="0 0 1"/> <parent link="left_leg_front"/><child link="tyer_slave_left_axis1"/><origin rpy="1.57075 0 0" xyz="0.02 0.0315 0.0"/><limit effort="100" velocity="100"/> <joint_properties damping="0.0" friction="0.0"/></joint><link name="tyer_slave_left_axis2"><visual><geometry><cylinder length=".06" radius="0.005"></cylinder></geometry><material name="yellow"><color rgba="1 1 0 1"/></material> </visual></link><joint name="right_leg_to_slave_left_axix2" type="continuous"><axis xyz="0 0 1"/> <parent link="left_leg"/><child link="tyer_slave_left_axis2"/><origin rpy="1.57075 0 0" xyz="0.063 0.0315 -0.0405"/><limit effort="100" velocity="100"/> <joint_properties damping="0.0" friction="0.0"/></joint><link name="tyer_slave_left_axis3"><visual><geometry><cylinder length=".06" radius="0.005"></cylinder></geometry><material name="yellow"><color rgba="1 1 0 1"/></material> </visual></link><joint name="right_leg_to_slave_left_axix3" type="continuous"><axis xyz="0 0 1"/> <parent link="left_leg"/><child link="tyer_slave_left_axis3"/><origin rpy="1.57075 0 0" xyz="0.008 0.0315 -0.0405"/><limit effort="100" velocity="100"/> <joint_properties damping="0.0" friction="0.0"/></joint><link name="tyer_slave_left_axis4"><visual><geometry><cylinder length=".06" radius="0.005"></cylinder></geometry><material name="yellow"><color rgba="1 1 0 1"/></material> </visual></link><joint name="right_leg_to_slave_left_axix4" type="continuous"><axis xyz="0 0 1"/> <parent link="left_leg"/><child link="tyer_slave_left_axis4"/><origin rpy="1.57075 0 0" xyz="-0.047 0.0315 -0.0405"/><limit effort="100" velocity="100"/> <joint_properties damping="0.0" friction="0.0"/></joint> <link name="tyer_slave_left_axis5"><visual><geometry><cylinder length=".06" radius="0.005"></cylinder></geometry><material name="yellow"><color rgba="1 1 0 1"/></material> </visual></link><joint name="right_leg_to_slave_left_axix5" type="continuous"><axis xyz="0 0 1"/> <parent link="left_leg_back"/><child link="tyer_slave_left_axis5"/><origin rpy="1.57075 0 0" xyz="-0.018 0.0315 -0.008"/><limit effort="100" velocity="100"/> <joint_properties damping="0.0" friction="0.0"/></joint>
8.增加主动轮
<link name="tyer_master_left"><visual><geometry><cylinder length=".03" radius="0.0275"></cylinder></geometry><material name="green"><color rgba="0 1 0 1"/></material> </visual></link><joint name="right_leg_to_master_left" type="fixed"><axis xyz="0 0 1"/> <parent link="tyer_master_left_axis"/><child link="tyer_master_left"/><origin rpy="0 0 0" xyz="0.0 0.0025 0.00"/><limit effort="100" velocity="100"/> <joint_properties damping="0.0" friction="0.0"/></joint> <link name="tyer_master_right"><visual><geometry><cylinder length=".03" radius="0.0275"></cylinder></geometry><material name="green"><color rgba="0 1 0 1"/></material> </visual></link><joint name="right_leg_to_master_right" type="fixed"><axis xyz="0 0 1"/> <parent link="tyer_master_right_axis"/><child link="tyer_master_right"/><origin rpy="0 0 0" xyz="0.0 -0.0025 0.00"/><limit effort="100" velocity="100"/> <joint_properties damping="0.0" friction="0.0"/></joint>
9.增加从动轮
<link name="tyer_slave1_left"><visual><geometry><cylinder length=".024" radius="0.0275"></cylinder></geometry><material name="green"><color rgba="0 1 0 1"/></material> </visual></link><joint name="right_leg_to_slave1_left" type="fixed"><axis xyz="0 0 1"/> <parent link="tyer_slave_left_axis1"/><child link="tyer_slave1_left"/><origin rpy="0 0 0" xyz="0.0 0.0025 0.00"/><limit effort="100" velocity="100"/> <joint_properties damping="0.0" friction="0.0"/></joint> <link name="tyer_slave2_left"><visual><geometry><cylinder length=".024" radius="0.0275"></cylinder></geometry><material name="green"><color rgba="0 1 0 1"/></material> </visual></link><joint name="right_leg_to_slave2_left" type="fixed"><axis xyz="0 0 1"/> <parent link="tyer_slave_left_axis2"/><child link="tyer_slave2_left"/><origin rpy="0 0 0" xyz="0.0 0.0025 0.00"/><limit effort="100" velocity="100"/> <joint_properties damping="0.0" friction="0.0"/></joint> <link name="tyer_slave3_left"><visual><geometry><cylinder length=".024" radius="0.0275"></cylinder></geometry><material name="green"><color rgba="0 1 0 1"/></material> </visual></link><joint name="right_leg_to_slave3_left" type="fixed"><axis xyz="0 0 1"/> <parent link="tyer_slave_left_axis3"/><child link="tyer_slave3_left"/><origin rpy="0 0 0" xyz="0.0 0.0025 0.00"/><limit effort="100" velocity="100"/> <joint_properties damping="0.0" friction="0.0"/></joint> <link name="tyer_slave4_left"><visual><geometry><cylinder length=".024" radius="0.0275"></cylinder></geometry><material name="green"><color rgba="0 1 0 1"/></material> </visual></link><joint name="right_leg_to_slave4_left" type="fixed"><axis xyz="0 0 1"/> <parent link="tyer_slave_left_axis4"/><child link="tyer_slave4_left"/><origin rpy="0 0 0" xyz="0.0 0.0025 0.00"/><limit effort="100" velocity="100"/> <joint_properties damping="0.0" friction="0.0"/></joint> <link name="tyer_slave5_left"><visual><geometry><cylinder length=".024" radius="0.0275"></cylinder></geometry><material name="green"><color rgba="0 1 0 1"/></material> </visual></link><joint name="right_leg_to_slave5_left" type="fixed"><axis xyz="0 0 1"/> <parent link="tyer_slave_left_axis5"/><child link="tyer_slave5_left"/><origin rpy="0 0 0" xyz="0.0 0.0025 0.00"/><limit effort="100" velocity="100"/> <joint_properties damping="0.0" friction="0.0"/></joint> <link name="tyer_slave1_right"><visual><geometry><cylinder length=".024" radius="0.0275"></cylinder></geometry><material name="green"><color rgba="0 1 0 1"/></material> </visual></link><joint name="right_leg_to_slave1_right" type="fixed"><axis xyz="0 0 1"/> <parent link="tyer_slave_right_axis1"/><child link="tyer_slave1_right"/><origin rpy="0 0 0" xyz="0.0 -0.0025 0.00"/><limit effort="100" velocity="100"/> <joint_properties damping="0.0" friction="0.0"/></joint> <link name="tyer_slave2_right"><visual><geometry><cylinder length=".024" radius="0.0275"></cylinder></geometry><material name="green"><color rgba="0 1 0 1"/></material> </visual></link><joint name="right_leg_to_slave2_right" type="fixed"><axis xyz="0 0 1"/> <parent link="tyer_slave_right_axis2"/><child link="tyer_slave2_right"/><origin rpy="0 0 0" xyz="0.0 -0.0025 0.00"/><limit effort="100" velocity="100"/> <joint_properties damping="0.0" friction="0.0"/></joint><link name="tyer_slave3_right"><visual><geometry><cylinder length=".024" radius="0.0275"></cylinder></geometry><material name="green"><color rgba="0 1 0 1"/></material> </visual></link><joint name="right_leg_to_slave3_right" type="fixed"><axis xyz="0 0 1"/> <parent link="tyer_slave_right_axis3"/><child link="tyer_slave3_right"/><origin rpy="0 0 0" xyz="0.0 -0.0025 0.00"/><limit effort="100" velocity="100"/> <joint_properties damping="0.0" friction="0.0"/></joint> <link name="tyer_slave4_right"><visual><geometry><cylinder length=".024" radius="0.0275"></cylinder></geometry><material name="green"><color rgba="0 1 0 1"/></material> </visual></link><joint name="right_leg_to_slave4_right" type="fixed"><axis xyz="0 0 1"/> <parent link="tyer_slave_right_axis4"/><child link="tyer_slave4_right"/><origin rpy="0 0 0" xyz="0.0 -0.0025 0.00"/><limit effort="100" velocity="100"/> <joint_properties damping="0.0" friction="0.0"/></joint> <link name="tyer_slave5_right"><visual><geometry><cylinder length=".024" radius="0.0275"></cylinder></geometry><material name="green"><color rgba="0 1 0 1"/></material> </visual></link><joint name="right_leg_to_slave5_right" type="fixed"><axis xyz="0 0 1"/> <parent link="tyer_slave_right_axis5"/><child link="tyer_slave5_right"/><origin rpy="0 0 0" xyz="0.0 -0.0025 0.00"/><limit effort="100" velocity="100"/> <joint_properties damping="0.0" friction="0.0"/></joint>
10.增加履带,这里用巨型拼接,主要是要计算好角度,但效果不是很好
<link name="caterpilar_left1"><visual><geometry><box size="0.10 .045 .0015"/></geometry><material name="black"><color rgba="0 0 0 1"/></material> </visual></link> <joint name="tyer_master_left_motor_to_caterpilar_left1" type="fixed"><parent link="tyer_master_left_motor"/><child link="caterpilar_left1"/><origin rpy="1.57075 0 -0.24178" xyz="0.05 0.02 -0.068"/><limit effort="100" velocity="100"/> <joint_properties damping="0.0" friction="0.0"/></joint> <link name="caterpilar_left2"><visual><geometry><box size="0.16 .045 .0015"/></geometry><material name="black"><color rgba="0 0 0 1"/></material> </visual></link> <joint name="tyer_master_left_motor_to_caterpilar_left2" type="fixed"><parent link="tyer_master_left_motor"/><child link="caterpilar_left2"/><origin rpy="1.57075 0 0.38178" xyz="-0.080 -0.00 -0.068"/><limit effort="100" velocity="100"/> <joint_properties damping="0.0" friction="0.0"/></joint> <link name="caterpilar_left3"><visual><geometry><box size="0.07 .045 .0015"/></geometry><material name="black"><color rgba="0 0 0 1"/></material> </visual></link> <joint name="tyer_master_left_motor_to_caterpilar_left3" type="fixed"><parent link="tyer_slave2_left"/><child link="caterpilar_left3"/><origin rpy="1.57075 0 0.64178" xyz="0.0405 -0.0065 -0.002"/><limit effort="100" velocity="100"/> <joint_properties damping="0.0" friction="0.0"/></joint> <link name="caterpilar_left4"><visual><geometry><box size="0.18 .045 .0015"/></geometry><material name="black"><color rgba="0 0 0 1"/></material> </visual></link> <joint name="tyer_master_left_motor_to_caterpilar_left4" type="fixed"><parent link="tyer_slave2_left"/><child link="caterpilar_left4"/><origin rpy="1.57075 0 0" xyz="-0.09 -0.028 -0.002"/><limit effort="100" velocity="100"/> <joint_properties damping="0.0" friction="0.0"/></joint> <link name="caterpilar_right1"><visual><geometry><box size="0.10 .045 .0015"/></geometry><material name="black"><color rgba="0 0 0 1"/></material> </visual></link> <joint name="tyer_master_left_motor_to_caterpilar_right1" type="fixed"><parent link="tyer_master_right_motor"/><child link="caterpilar_right1"/><origin rpy="1.57075 0 -0.24178" xyz="0.05 0.02 0.068"/><limit effort="100" velocity="100"/> <joint_properties damping="0.0" friction="0.0"/></joint> <link name="caterpilar_right2"><visual><geometry><box size="0.16 .045 .0015"/></geometry><material name="black"><color rgba="0 0 0 1"/></material> </visual></link> <joint name="tyer_master_left_motor_to_caterpilar_right2" type="fixed"><parent link="tyer_master_right_motor"/><child link="caterpilar_right2"/><origin rpy="1.57075 0 0.38178" xyz="-0.080 -0.00 0.068"/><limit effort="100" velocity="100"/> <joint_properties damping="0.0" friction="0.0"/></joint> <link name="caterpilar_right3"><visual><geometry><box size="0.07 .045 .0015"/></geometry><material name="black"><color rgba="0 0 0 1"/></material> </visual></link> <joint name="tyer_master_left_motor_to_caterpilar_right3" type="fixed"><parent link="tyer_slave2_right"/><child link="caterpilar_right3"/><origin rpy="1.57075 0 0.64178" xyz="0.0405 -0.0065 0.002"/><limit effort="100" velocity="100"/> <joint_properties damping="0.0" friction="0.0"/></joint> <link name="caterpilar_right4"><visual><geometry><box size="0.18 .045 .0015"/></geometry><material name="black"><color rgba="0 0 0 1"/></material> </visual></link> <joint name="tyer_master_left_motor_to_caterpilar_right4" type="fixed"><parent link="tyer_slave2_right"/><child link="caterpilar_right4"/><origin rpy="1.57075 0 0" xyz="-0.09 -0.028 0.002"/><limit effort="100" velocity="100"/> <joint_properties damping="0.0" friction="0.0"/></joint>
11.增加身体
<link name="body"><visual><geometry><box size="0.19 .11 .08"/></geometry><material name="blue"><color rgba="0 0 255 1"/></material> </visual></link> <joint name="base_to_body" type="fixed"><parent link="base_link"/><child link="body"/><origin xyz="0.0 0.0 0.04"/></joint>
12.增加xtion pro,用矩形拼接
<link name="xtion_camera_base"><visual><geometry><box size="0.038 .10 .025"/></geometry><material name="black"><color rgba="0 0 1 1"/></material> </visual></link> <joint name="body_to_xtion_camera_base" type="fixed"><parent link="body"/><child link="xtion_camera_base"/><origin xyz="0.076 0.0 0.0525"/></joint><link name="xtion_camera_base_neck"><visual><geometry><box size="0.020 .020 .020"/></geometry><material name="black"><color rgba="0 0 50 1"/></material> </visual></link> <joint name="xtion_camera_base_to_neck" type="fixed"><parent link="xtion_camera_base"/><child link="xtion_camera_base_neck"/><origin xyz="0.009 0.0 0.0125"/></joint> <link name="xtion_camera"><visual><geometry><box size="0.038 .18 .027"/></geometry><material name="black"><color rgba="0 0 1 1"/></material> </visual></link> <joint name="xtion_camera_base_neck_to_camera" type="fixed"><parent link="xtion_camera_base_neck"/><child link="xtion_camera"/><origin xyz="0.0 0.0 0.0235"/></joint><link name="xtion_camera_eye_left"><visual><geometry><cylinder length=".002" radius="0.005"></cylinder></geometry><material name="yellow"><color rgba="1 1 0 1"/></material> </visual></link><joint name="xtion_camera_to_eye_left" type="fixed"><axis xyz="0 0 1"/> <parent link="xtion_camera"/><child link="xtion_camera_eye_left"/><origin rpy="0 1.57075 0" xyz="0.0191 0.045 0.0"/><limit effort="100" velocity="100"/> <joint_properties damping="0.0" friction="0.0"/></joint> <link name="xtion_camera_eye_right"><visual><geometry><cylinder length=".002" radius="0.005"></cylinder></geometry><material name="yellow"><color rgba="1 1 0 1"/></material> </visual></link><joint name="xtion_camera_to_eye_right" type="fixed"><axis xyz="0 0 1"/> <parent link="xtion_camera"/><child link="xtion_camera_eye_right"/><origin rpy="0 1.57075 0" xyz="0.0191 -0.045 0.0"/><limit effort="100" velocity="100"/> <joint_properties damping="0.0" friction="0.0"/></joint>
13.增加左右肩部XZ平面旋转舵机
<!-- left_shoulder stevo--><link name="left_shoulder_stevo"><visual><geometry><box size="0.054 .0403 .027"/></geometry><material name="black"><color rgba="1 1 0 1"/></material> </visual></link> <joint name="body_to_left_shoulder_stevo" type="fixed"><parent link="body"/><child link="left_shoulder_stevo"/><origin xyz="0.04 0.035 0.026"/></joint> <link name="left_shoulder_stevo_axis"><visual><geometry><cylinder length=".04" radius="0.0029"></cylinder></geometry><material name="yellow"><color rgba="1 1 0 1"/></material> </visual></link><joint name="left_shoulder_stevo_to_axis" type="revolute"><axis xyz="0 0 1"/> <parent link="left_shoulder_stevo"/><child link="left_shoulder_stevo_axis"/><origin rpy="1.57075 0 0" xyz="0.0 0.027 0.0"/><limit effort="100" velocity="100" lower="0" upper="3.1415926"/> <joint_properties damping="0.0" friction="0.0"/></joint> <!-- righ_shoulder stevo 6--><link name="right_shoulder_stevo"><visual><geometry><box size="0.054 .0403 .027"/></geometry><material name="black"><color rgba="1 1 0 1"/></material> </visual></link> <joint name="body_to_right_shoulder_stevo" type="fixed"><parent link="body"/><child link="right_shoulder_stevo"/><origin xyz="0.04 -0.035 0.026"/></joint> <link name="right_shoulder_stevo_axis"><visual><geometry><cylinder length=".04" radius="0.0029"></cylinder></geometry><material name="yellow"><color rgba="1 1 0 1"/></material> </visual></link><joint name="right_shoulder_stevo_to_axis" type="revolute"><axis xyz="0 0 1"/> <parent link="right_shoulder_stevo"/><child link="right_shoulder_stevo_axis"/><origin rpy="1.57075 0 0" xyz="0.0 -0.027 0.0"/><limit effort="100" velocity="100" lower="0" upper="3.1415926"/> <joint_properties damping="0.0" friction="0.0"/></joint>
14.肩部摆动的舵机
<!-- left_shoulder stevo lift --><link name="left_shoulder_stevo_lift"><visual><geometry><box size="0.054 .0403 .027"/></geometry><material name="black"><color rgba="1 1 0 1"/></material> </visual></link> <joint name="left_shoulder_stevo_axis_to_lift_stevo" type="fixed"><parent link="left_shoulder_stevo_axis"/><child link="left_shoulder_stevo_lift"/><origin xyz="0.0 -0.01015 -0.028"/></joint><link name="left_shoulder_stevo_lift_axis"><visual><geometry><cylinder length=".0704" radius="0.0029"></cylinder></geometry><material name="yellow"><color rgba="1 1 0 1"/></material> </visual></link><joint name="left_shoulder_stevo_lift_to_axis" type="continuous"><axis xyz="0 0 1"/> <parent link="left_shoulder_stevo_lift"/><child link="left_shoulder_stevo_lift_axis"/><origin rpy="1.57075 0 0" xyz="0.0135 0.0 0.0"/><limit effort="100" velocity="100"/> <joint_properties damping="0.0" friction="0.0"/></joint><!-- right_shoulder stevo lift--><link name="right_shoulder_stevo_lift"><visual><geometry><box size="0.054 .0403 .027"/></geometry><material name="black"><color rgba="1 1 0 1"/></material> </visual></link> <joint name="right_shoulder_stevo_axis_to_lift_stevo" type="fixed"><parent link="right_shoulder_stevo_axis"/><child link="right_shoulder_stevo_lift"/><origin xyz="0.0 -0.01015 0.028"/></joint><link name="right_shoulder_stevo_lift_axis"><visual><geometry><cylinder length=".0704" radius="0.0029"></cylinder></geometry><material name="yellow"><color rgba="1 1 0 1"/></material> </visual></link><joint name="right_shoulder_stevo_lift_to_axis" type="continuous"><axis xyz="0 0 1"/> <parent link="right_shoulder_stevo_lift"/><child link="right_shoulder_stevo_lift_axis"/><origin rpy="1.57075 0 0" xyz="0.0135 0.0 0.0"/><limit effort="100" velocity="100"/> <joint_properties damping="0.0" friction="0.0"/></joint>
15.上臂
<!-- left_big arm --><link name="left_big_arm_up"><visual><geometry><box size="0.145 .027 .002"/></geometry><material name="sliver"><color rgba="223 223 223 1"/></material> </visual></link> <joint name="left_shoulder_stevo_lift_axis_to_left_big_arm" type="fixed"><parent link="left_shoulder_stevo_lift_axis"/><child link="left_big_arm_up"/><origin xyz="0.059 0.0 -0.035"/></joint> <link name="left_big_arm_down"><visual><geometry><box size="0.145 .027 .002"/></geometry><material name="sliver"><color rgba="223 223 223 1"/></material> </visual></link> <joint name="left_big_arm_up_to_left_big_arm_down" type="fixed"><parent link="left_big_arm_up"/><child link="left_big_arm_down"/><origin xyz="0.0 0.0 0.07"/></joint> <!-- right_big arm --><link name="right_big_arm_up"><visual><geometry><box size="0.145 .027 .002"/></geometry><material name="sliver"><color rgba="223 223 223 1"/></material> </visual></link> <joint name="right_shoulder_stevo_lift_axis_to_right_big_arm" type="fixed"><parent link="right_shoulder_stevo_lift_axis"/><child link="right_big_arm_up"/><origin xyz="0.059 0.0 -0.035"/></joint> <link name="right_big_arm_down"><visual><geometry><box size="0.145 .027 .002"/></geometry><material name="sliver"><color rgba="223 223 223 1"/></material> </visual></link> <joint name="right_big_arm_up_to_right_big_arm_down" type="fixed"><parent link="right_big_arm_up"/><child link="right_big_arm_down"/><origin xyz="0.0 0.0 0.07"/></joint>
16.肘部关键舵机
<!--left arm stevo--><link name="left_arm_stevo_axis"><visual><geometry><cylinder length=".0704" radius="0.0029"></cylinder></geometry><material name="yellow"><color rgba="1 1 0 1"/></material> </visual></link><joint name="left_big_arm_up_to_axis" type="revolute"><axis xyz="0 0 1"/> <parent link="left_big_arm_up"/><child link="left_arm_stevo_axis"/><origin rpy="0 0 0.5" xyz="0.059 0.0 0.0352"/><limit effort="100" velocity="100" lower="0" upper="3.1415926"/> <joint_properties damping="0.0" friction="0.0"/></joint> <link name="left_arm_stevo"><visual><geometry><box size="0.054 .027 .0403"/></geometry><material name="black"><color rgba="1 1 0 1"/></material> </visual></link> <joint name="left_big_arm_up_to_axis_to_left_arm_stevo" type="fixed"><parent link="left_arm_stevo_axis"/><child link="left_arm_stevo"/><origin xyz="0.0135 0.0 0.0"/></joint> <!--right arm stevo--><link name="right_arm_stevo_axis"><visual><geometry><cylinder length=".0704" radius="0.0029"></cylinder></geometry><material name="yellow"><color rgba="1 1 0 1"/></material> </visual></link><joint name="right_big_arm_up_to_axis" type="revolute"><axis xyz="0 0 1"/> <parent link="right_big_arm_up"/><child link="right_arm_stevo_axis"/><origin rpy="0 0 -0.5" xyz="0.059 0.0 0.0352"/><limit effort="100" velocity="100" lower="0" upper="3.1415926"/> <joint_properties damping="0.0" friction="0.0"/></joint> <link name="right_arm_stevo"><visual><geometry><box size="0.054 .027 .0403"/></geometry><material name="black"><color rgba="1 1 0 1"/></material> </visual></link> <joint name="right_big_arm_up_to_axis_to_right_arm_stevo" type="fixed"><parent link="right_arm_stevo_axis"/><child link="right_arm_stevo"/><origin xyz="0.0135 0.0 0.0"/></joint>
17.小臂
<!-- left_small arm --><link name="left_small_arm_up"><visual><geometry><box size="0.0725 .027 .002"/></geometry><material name="sliver"><color rgba="223 223 223 1"/></material> </visual></link> <joint name="left_arm_stevo_to_left_small_arm_up" type="fixed"><parent link="left_arm_stevo"/><child link="left_small_arm_up"/><origin xyz="0.059 0.0 -0.035"/></joint> <link name="left_small_arm_down"><visual><geometry><box size="0.0725 .027 .002"/></geometry><material name="sliver"><color rgba="223 223 223 1"/></material> </visual></link> <joint name="left_small_arm_up_to_left_small_arm_down" type="fixed"><parent link="left_small_arm_up"/><child link="left_small_arm_down"/><origin xyz="0.0 0.0 0.07"/></joint> <link name="left_small_arm_middle"><visual><geometry><box size="0.07 .027 .002"/></geometry><material name="sliver"><color rgba="223 223 223 1"/></material> </visual></link> <joint name="left_small_arm_up_to_left_small_arm_middle" type="fixed"><parent link="left_small_arm_up"/><child link="left_small_arm_middle"/><origin rpy="0 1.57075 0" xyz="-0.035 0.0 0.035"/></joint> <!-- right_small arm --><link name="right_small_arm_up"><visual><geometry><box size="0.0725 .027 .002"/></geometry><material name="sliver"><color rgba="223 223 223 1"/></material> </visual></link> <joint name="right_arm_stevo_to_right_small_arm_up" type="fixed"><parent link="right_arm_stevo"/><child link="right_small_arm_up"/><origin xyz="0.059 0.0 -0.035"/></joint> <link name="right_small_arm_down"><visual><geometry><box size="0.0725 .027 .002"/></geometry><material name="sliver"><color rgba="223 223 223 1"/></material> </visual></link> <joint name="right_small_arm_up_to_right_small_arm_down" type="fixed"><parent link="right_small_arm_up"/><child link="right_small_arm_down"/><origin xyz="0.0 0.0 0.07"/></joint> <link name="right_small_arm_middle"><visual><geometry><box size="0.07 .027 .002"/></geometry><material name="sliver"><color rgba="223 223 223 1"/></material> </visual></link> <joint name="right_small_arm_up_to_right_small_arm_middle" type="fixed"><parent link="right_small_arm_up"/><child link="right_small_arm_middle"/><origin rpy="0 1.57075 0" xyz="-0.035 0.0 0.035"/></joint>
18.手腕手臂方向关节舵机
<!--left wrist stevo--><link name="left_wrist_stevo_axis"><visual><geometry><cylinder length=".0704" radius="0.0029"></cylinder></geometry><material name="yellow"><color rgba="1 1 0 1"/></material> </visual></link><joint name="left_small_arm_up_to_axis" type="revolute"><axis xyz="0 0 1"/> <parent link="left_small_arm_up"/><child link="left_wrist_stevo_axis"/><origin rpy="0 0 0.5" xyz="0.0295 0.0 0.0352"/><limit effort="100" velocity="100" lower="0" upper="3.1415926"/> <joint_properties damping="0.0" friction="0.0"/></joint> <link name="left_wrist_stevo"><visual><geometry><box size="0.054 .027 .0403"/></geometry><material name="black"><color rgba="1 1 0 1"/></material> </visual></link> <joint name="left_small_arm_up_to_axis_to_left_axis_stevo" type="fixed"><parent link="left_wrist_stevo_axis"/><child link="left_wrist_stevo"/><origin xyz="0.0135 0.0 0.0"/></joint> <!--right wrist stevo--><link name="right_wrist_stevo_axis"><visual><geometry><cylinder length=".0704" radius="0.0029"></cylinder></geometry><material name="yellow"><color rgba="1 1 0 1"/></material> </visual></link><joint name="right_small_arm_up_to_axis" type="revolute"><axis xyz="0 0 1"/> <parent link="right_small_arm_up"/><child link="right_wrist_stevo_axis"/><origin rpy="0 0 -0.5" xyz="0.0295 0.0 0.0352"/><limit effort="100" velocity="100" lower="0" upper="3.1415926"/> <joint_properties damping="0.0" friction="0.0"/></joint> <link name="right_wrist_stevo"><visual><geometry><box size="0.054 .027 .0403"/></geometry><material name="black"><color rgba="1 1 0 1"/></material> </visual></link> <joint name="right_small_arm_up_to_axis_to_right_axis_stevo" type="fixed"><parent link="right_wrist_stevo_axis"/><child link="right_wrist_stevo"/><origin xyz="0.0135 0.0 0.0"/></joint>
19.手腕旋转关节舵机
<!--left wrist run stevo--><link name="left_wrist_run_stevo"><visual><geometry><box size="0.054 .027 .0403"/></geometry><material name="color1"><color rgba="0 255 255 1 "/></material> </visual></link> <joint name="right_wrist_stevo_to_left_wrist_run_stevo" type="fixed"><parent link="left_wrist_stevo"/><child link="left_wrist_run_stevo"/><origin rpy="0 1.57075 0" xyz="0.0135 -0.027 0.0"/></joint> <link name="left_wrist_run_stevo_axis"><visual><geometry><cylinder length=".04" radius="0.0029"></cylinder></geometry><material name="yellow"><color rgba="1 1 0 1"/></material> </visual></link><joint name="left_wrist_run_stevo_to_axis" type="revolute"><axis xyz="0 0 1"/> <parent link="left_wrist_run_stevo"/><child link="left_wrist_run_stevo_axis"/><origin rpy="0 0 0" xyz="0.0135 0 0.020"/><limit effort="100" velocity="100" lower="0" upper="3.1415926"/> <joint_properties damping="0.0" friction="0.0"/></joint><!--right wrist run stevo--><link name="right_wrist_run_stevo"><visual><geometry><box size="0.054 .027 .0403"/></geometry><material name="color1"><color rgba="0 255 255 1 "/></material> </visual></link> <joint name="right_wrist_stevo_to_right_wrist_run_stevo" type="fixed"><parent link="right_wrist_stevo"/><child link="right_wrist_run_stevo"/><origin rpy="0 1.57075 0" xyz="0.0135 0.027 0.0"/></joint> <link name="right_wrist_run_stevo_axis"><visual><geometry><cylinder length=".04" radius="0.0029"></cylinder></geometry><material name="yellow"><color rgba="1 1 0 1"/></material> </visual></link><joint name="right_wrist_run_stevo_to_axis" type="revolute"><axis xyz="0 0 1"/> <parent link="right_wrist_run_stevo"/><child link="right_wrist_run_stevo_axis"/><origin rpy="0 0 0" xyz="0.0135 0 0.020"/><limit effort="100" velocity="100" lower="0" upper="3.1415926"/> <joint_properties damping="0.0" friction="0.0"/></joint>
20.手部抓取舵机
<!--left wrist run stevo--><link name="left_hand_run_stevo"><visual><geometry><box size="0.054 .027 .0403"/></geometry><material name="black"><color rgba="0 0 0 1 "/></material> </visual></link> <joint name="left_wrist_run_stevo_axis_to_left_hand_run_stevo" type="fixed"><parent link="left_wrist_run_stevo_axis"/><child link="left_hand_run_stevo"/><origin rpy="1.57075 0 0" xyz="0.0 0.0 0.0335"/></joint> <link name="left_hand_run_stevo_axis"><visual><geometry><cylinder length=".04" radius="0.0029"></cylinder></geometry><material name="yellow"><color rgba="1 1 0 1"/></material> </visual></link><joint name="left_hand_run_stevo_to_left_hand_run_stevo" type="revolute"><axis xyz="0 0 1"/> <parent link="left_hand_run_stevo"/><child link="left_hand_run_stevo_axis"/><origin rpy="0 0 0" xyz="0.0135 0 0.0135"/><limit effort="100" velocity="100" lower="0" upper="3.1415926"/> <joint_properties damping="0.0" friction="0.0"/></joint> <!--right wrist run stevo--><link name="right_hand_run_stevo"><visual><geometry><box size="0.054 .027 .0403"/></geometry><material name="black"><color rgba="0 0 0 1 "/></material> </visual></link> <joint name="right_wrist_run_stevo_axis_to_right_hand_run_stevo" type="fixed"><parent link="right_wrist_run_stevo_axis"/><child link="right_hand_run_stevo"/><origin rpy="1.57075 0 0" xyz="0.0 0.0 0.0335"/></joint> <link name="right_hand_run_stevo_axis"><visual><geometry><cylinder length=".04" radius="0.0029"></cylinder></geometry><material name="yellow"><color rgba="1 1 0 1"/></material> </visual></link><joint name="right_hand_run_stevo_to_right_hand_run_stevo" type="revolute"><axis xyz="0 0 1"/> <parent link="right_hand_run_stevo"/><child link="right_hand_run_stevo_axis"/><origin rpy="0 0 0" xyz="0.0135 0 -0.0135"/><limit effort="100" velocity="100" lower="0" upper="3.1415926"/> <joint_properties damping="0.0" friction="0.0"/></joint>
21.手指用标准urdf元素很难描述出来,这里先只简单的放一根手指,后续在修改。
<!--left finger--><link name="left_finger"><visual><geometry><box size="0.0375 .0135 .002"/></geometry><material name="sliver"><color rgba="223 223 223 1"/></material> </visual></link> <joint name="left_hand_run_stevo_axis_to_left_finger" type="fixed"><parent link="left_hand_run_stevo_axis"/><child link="left_finger"/><origin rpy="0 0 1.57075" xyz="0.0 0.0173 0.02"/></joint> <!--right finger--><link name="right_finger"><visual><geometry><box size="0.0375 .0135 .002"/></geometry><material name="sliver"><color rgba="223 223 223 1"/></material> </visual></link> <joint name="right_hand_run_stevo_axis_to_right_finger" type="fixed"><parent link="right_hand_run_stevo_axis"/><child link="right_finger"/><origin rpy="0 0 1.57075" xyz="0.0 0.0173 -0.02"/></joint>