紧急通知:禁止一切关于政治&VPN翻墙等话题,发现相关帖子会立马删除封号
小鱼 ROS 2 新书上线!点击链接查看, 新书配套视频点击链接查看。
提问前必看的发帖注意事项—— 提问前必看!不符合要求的问题拒绝回答!!
社区使用指南—如何添加标签修改密码
小鱼 ROS 2 新书上线!点击链接查看, 新书配套视频点击链接查看。
提问前必看的发帖注意事项—— 提问前必看!不符合要求的问题拒绝回答!!
社区使用指南—如何添加标签修改密码
使用moveit导入urdf后生成的机械臂在gazebo内底座不是固定于地面的
-
开发环境:ubuntu20.04 noetic Gazebo multi-robot simulator, version 11.11.0
现存问题是:使用moveit生成的demo_gazebo.launch文件时rivz内机械臂一切正常,可以正常使用moveit功能,gazebo内的机械臂同样可以跟随rviz内机械臂的运动,但gazebo内的机械臂的rootlink没有固定在地面,机械臂运动时会在地面上来回翻滚。
尝试过额外添加虚拟link。<link name="worldbase"></link> <joint name="base_to_wrold" type="revolute"> <parent link="worldbase"/> <!-- Connect link1 to base_virtual instead of base --> <child link="base"/> <!-- Existing joint content --> </joint>
尝试过添加static
<gazebo reference="base"> <static>true</static> </gazebo>
原本的urdf文件内不存在转动惯量以及gazebo的transmission标签部分的内容,这些内容都是依靠moveit进行生成的。包括现有再用的所有配置文件以及launch文件都是依靠moveit生成的。
以下是当前正在使用的urdf文件:<?xml version="1.0" ?> <robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="firefighter"> <xacro:property name="width" value=".2" /> <link name="base"> <visual> <geometry> <!--- 0.0 0 -0.04 1.5708 3.14159--> <mesh filename="package://display/urdf/mycobot/base.dae" /> </geometry> <origin xyz="0 0 0 " rpy=" 0 0 0" /> </visual> <collision> <geometry> <!--- 0.0 0 -0.04 1.5708 3.14159--> <mesh filename="package://display/urdf/mycobot/base.dae" /> </geometry> <origin xyz="0 0 0 " rpy=" 0 0 0" /> </collision> <inertial> <mass value="1000000" /> <origin xyz="0 0 0" rpy="0 0 0" /> <inertia ixx="0.03" iyy="0.03" izz="0.03" ixy="0.0" ixz="0.0" iyz="0.0" /> </inertial> </link> <link name="link1"> <visual> <geometry> <mesh filename="package://display/urdf/mycobot/link1.dae" /> </geometry> <origin xyz="0 0 0 " rpy="0 0 3.1415926" /> </visual> <collision> <geometry> <mesh filename="package://display/urdf/mycobot/link1.dae" /> </geometry> <origin xyz="0 0 0 " rpy=" 0 0 3.1415926" /> </collision> <inertial> <mass value="0.1" /> <origin xyz="0 0 0" rpy="0 0 0" /> <inertia ixx="0.03" iyy="0.03" izz="0.03" ixy="0.0" ixz="0.0" iyz="0.0" /> </inertial> </link> <link name="link2"> <visual> <geometry> <mesh filename="package://display/urdf/mycobot/link2.dae" /> </geometry> <origin xyz="0 0 -0.080 " rpy=" 3.1415926 0 3.1415926" /> </visual> <collision> <geometry> <mesh filename="package://display/urdf/mycobot/link2.dae" /> </geometry> <origin xyz="0 0 -0.080 " rpy=" 3.1415926 0 3.1415926" /> </collision> <inertial> <mass value="0.1" /> <origin xyz="0 0 0" rpy="0 0 0" /> <inertia ixx="0.03" iyy="0.03" izz="0.03" ixy="0.0" ixz="0.0" iyz="0.0" /> </inertial> </link> <link name="link3"> <visual> <geometry> <!--- 0.0 0 -0.04 --> <mesh filename="package://display/urdf/mycobot/link3.dae" /> </geometry> <origin xyz="0 0 -0.0855 " rpy=" 3.1415926 0 3.1415926" /> </visual> <collision> <geometry> <!--- 0.0 0 -0.04 --> <mesh filename="package://display/urdf/mycobot/link3.dae" /> </geometry> <origin xyz="0 0 -0.0855 " rpy="3.1415926 0 3.1415926" /> </collision> <inertial> <mass value="0.1" /> <origin xyz="0 0 0" rpy="0 0 0" /> <inertia ixx="0.03" iyy="0.03" izz="0.03" ixy="0.0" ixz="0.0" iyz="0.0" /> </inertial> </link> <link name="link4"> <visual> <geometry> <!--- 0.0 0 -0.04 --> <mesh filename="package://display/urdf/mycobot/link4.dae" /> </geometry> <origin xyz="0 0 0 " rpy=" 0 3.1415926 0" /> </visual> <collision> <geometry> <!--- 0.0 0 -0.04 --> <mesh filename="package://display/urdf/mycobot/link4.dae" /> </geometry> <origin xyz="0 0 0 " rpy=" 0 3.1415926 0" /> </collision> <inertial> <mass value="0.1" /> <origin xyz="0 0 0" rpy="0 0 0" /> <inertia ixx="0.03" iyy="0.03" izz="0.03" ixy="0.0" ixz="0.0" iyz="0.0" /> </inertial> </link> <link name="link5"> <visual> <geometry> <!--- 0.0 0 -0.04 --> <mesh filename="package://display/urdf/mycobot/link5.dae" /> </geometry> <origin xyz="0 0 0 " rpy=" 0 0 1.5707" /> </visual> <collision> <geometry> <!--- 0.0 0 -0.04 --> <mesh filename="package://display/urdf/mycobot/link5.dae" /> </geometry> <origin xyz="0 0 0 " rpy=" 0 0 1.5707" /> </collision> <inertial> <mass value="0.1" /> <origin xyz="0 0 0" rpy="0 0 0" /> <inertia ixx="0.03" iyy="0.03" izz="0.03" ixy="0.0" ixz="0.0" iyz="0.0" /> </inertial> </link> <link name="link6"> <visual> <geometry> <!--- 0.0 0 -0.04 --> <mesh filename="package://display/urdf/mycobot/link6.dae" /> </geometry> <material name="grey"> <color rgba="0.5 0.5 0.5 1" /> </material> <origin xyz="0.03 0 0" rpy=" 0 -1.5707 0" /> </visual> <collision> <geometry> <!--- 0.0 0 -0.04 --> <mesh filename="package://display/urdf/mycobot/link6.dae" /> </geometry> <material name="grey"> <color rgba="0.5 0.5 0.5 1" /> </material> <origin xyz="0.03 0 0" rpy=" 0 -1.5707 0" /> </collision> <inertial> <mass value="0.1" /> <origin xyz="0 0 0" rpy="0 0 0" /> <inertia ixx="0.03" iyy="0.03" izz="0.03" ixy="0.0" ixz="0.0" iyz="0.0" /> </inertial> </link> <joint name="joint2_to_joint1" type="revolute"> <axis xyz="0 0 1" /> <limit effort="1000.0" lower="-3.14" upper="3.14159" velocity="0" /> <parent link="base" /> <child link="link1" /> <origin xyz="0 0 0.19934" rpy="0 0 0" /> </joint> <joint name="joint3_to_joint2" type="revolute"> <axis xyz="0 0 -1" /> <limit effort="1000.0" lower="-4.71" upper="1.5708" velocity="0" /> <!-- <limit effort = "1000.0" lower = "-3.14" upper = "3.14" velocity = "0"/> --> <parent link="link1" /> <child link="link2" /> <!-- <origin xyz= "0 0 0" rpy = "1.5708 -1.5708 0"/> --> <origin xyz="0 0 0" rpy="1.5708 0 0" /> </joint> <joint name="joint4_to_joint3" type="revolute"> <axis xyz=" 0 0 -1" /> <limit effort="1000.0" lower="-2.61" upper="2.618" velocity="0" /> <parent link="link2" /> <child link="link3" /> <origin xyz="0.25 0 0 " rpy="0 0 0" /> </joint> <joint name="joint5_to_joint4" type="revolute"> <axis xyz=" 0 0 -1" /> <limit effort="1000.0" lower="-4.53" upper="1.3962" velocity="0" /> <!-- <limit effort = "1000.0" lower = "-2.96" upper = "2.97" velocity = "0"/> --> <parent link="link3" /> <child link="link4" /> <!-- <origin xyz= "0.25 0 -0.1091" rpy = "0 0 1.5708"/> --> <origin xyz="0.25 0 -0.1091" rpy="0 0 0" /> </joint> <joint name="joint6_to_joint5" type="revolute"> <axis xyz="0 0 1" /> <limit effort="1000.0" lower="-2.93" upper="2.9321" velocity="0" /> <parent link="link4" /> <child link="link5" /> <origin xyz="0 -0.108 0" rpy="1.57080 -1.57080 0" /> </joint> <joint name="joint6output_to_joint6" type="revolute"> <axis xyz="-1 0 0" /> <limit effort="1000.0" lower="-3.03" upper="3.0368" velocity="0" /> <parent link="link5" /> <child link="link6" /> <origin xyz="-0.07586 0 0" rpy="-1.57080 0 0 " /> </joint> <transmission name="trans_joint2_to_joint1"> <type>transmission_interface/SimpleTransmission</type> <joint name="joint2_to_joint1"> <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> </joint> <actuator name="joint2_to_joint1_motor"> <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> <mechanicalReduction>1</mechanicalReduction> </actuator> </transmission> <transmission name="trans_joint3_to_joint2"> <type>transmission_interface/SimpleTransmission</type> <joint name="joint3_to_joint2"> <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> </joint> <actuator name="joint3_to_joint2_motor"> <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> <mechanicalReduction>1</mechanicalReduction> </actuator> </transmission> <transmission name="trans_joint4_to_joint3"> <type>transmission_interface/SimpleTransmission</type> <joint name="joint4_to_joint3"> <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> </joint> <actuator name="joint4_to_joint3_motor"> <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> <mechanicalReduction>1</mechanicalReduction> </actuator> </transmission> <transmission name="trans_joint5_to_joint4"> <type>transmission_interface/SimpleTransmission</type> <joint name="joint5_to_joint4"> <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> </joint> <actuator name="joint5_to_joint4_motor"> <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> <mechanicalReduction>1</mechanicalReduction> </actuator> </transmission> <transmission name="trans_joint6_to_joint5"> <type>transmission_interface/SimpleTransmission</type> <joint name="joint6_to_joint5"> <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> </joint> <actuator name="joint6_to_joint5_motor"> <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> <mechanicalReduction>1</mechanicalReduction> </actuator> </transmission> <transmission name="trans_joint6output_to_joint6"> <type>transmission_interface/SimpleTransmission</type> <joint name="joint6output_to_joint6"> <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> </joint> <actuator name="joint6output_to_joint6_motor"> <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> <mechanicalReduction>1</mechanicalReduction> </actuator> </transmission> <gazebo> <plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so"> <robotNamespace>/</robotNamespace> </plugin> </gazebo> </robot>
-
@luoxihao2001 在 使用moveit导入urdf后生成的机械臂在gazebo内底座不是固定于地面的 中说:
<link name="worldbase"></link>
<joint name="base_to_wrold" type="revolute">
<parent link="worldbase"/> <!-- Connect link1 to base_virtual instead of base -->
<child link="base"/>
<!-- Existing joint content -->
</joint>这里写错了,我这里的joint tpye是fixed