阿克曼urdf模型构建错误
-
阿克曼urdf模型在构建的时候,同时加入左前轮和右前轮的转动连杆时,模型就显示错误,不加的话可以显示,但是无法正常控制使用,在gazebo设置中的wheels
<left_steering_joint>fr_left_steer_joint</left_steering_joint>
<right_steering_joint>fr_right_steer_joint</right_steering_joint>
这两句代码,加与不加的效果如下
这是不加的效果
这是加了的效果下面是完整的urdf代码
<!-- 底盘实现 -->
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="car">
<!-- 1、需要声明变量-->
<!-- PI值 -->
<xacro:property name="PI" value="3.1415927"/>
<!-- 底盘尺寸质量 -->
<xacro:property name="car_length" value="0.27"/>
<xacro:property name="car_width" value="0.185"/>
<xacro:property name="car_height" value="0.055"/>
<xacro:property name="car_mass" value="20"/><!-- 轮胎尺寸质量连杆质量 --> <xacro:property name="wheel_radius" value="0.0375"/> <xacro:property name="wheel_length" value="0.03"/> <xacro:property name="wheel_mass" value="2"/> <xacro:property name="steering_mass" value="0.01" /> <!-- 轮胎关节平移量 --> <xacro:property name="wheel_joint_x" value="0.085"/> <xacro:property name="wheel_joint_y" value="0.09"/> <xacro:property name="wheel_joint_z" value="${-(car_height/2 + distance - wheel_radius)}"/> <!-- 雷达属性 --> <xacro:property name="laser_radius" value="0.03"/> <xacro:property name="laser_length" value="0.03"/> <!-- 雷达关节偏移量 --> <xacro:property name="laser_joint_x" value="0.04"/> <xacro:property name="laser_joint_y" value="0.0"/> <xacro:property name="laser_joint_z" value="${car_height/2 + laser_length/2}"/> <!-- 离地间距 --> <xacro:property name="distance" value="0.07"/> <!-- 抽取颜色 --> <material name="black"> <color rgba="0.0 0.0 0.0 1.0"/> </material> <material name="white"> <color rgba="1.0 1.0 1.0 1.0"/> </material> <material name="blue"> <color rgba="0.0 0.0 0.4 1.0"/> </material> <!-- 2、设置base_footprint --> <link name="base_footprint"> <!-- <visual> <geometry> <sphere radius="0.001"/> </geometry> </visual> --> <origin xyz="0 0 0" rpy="0 0 0" /> </link> <!-- 3、设置base_link --> <link name="base_link"> <visual> <geometry> <box size="${car_length} ${car_width} ${car_height}"/> </geometry> <origin xyz="0 0 0 " rpy="0 0 0"/> <material name="white"/> </visual> <!-- 3-1、设置碰撞参数 --> <collision> <geometry> <box size="${car_length} ${car_width} ${car_height}"/> </geometry> <origin xyz="0 0 0 " rpy="0 0 0"/> </collision> <!-- 3-2、设置惯性矩阵 --> <inertial> <mass value="${car_mass}" /> <inertia ixx="${car_mass/12 * (car_width*car_width + car_height*car_height)}" ixy="0" ixz="0" iyy="${car_mass/12 * (car_length*car_length + car_height*car_height)}" iyz="0" izz="${car_mass/12 * (car_width*car_width + car_length*car_length)}" /> </inertial> </link> <!-- 3-3 gazebo设置颜色 --> <gazebo reference="base_link"> <material>Gazebo/White</material> </gazebo> <!-- 3-4、使用joint将二者关联 --> <joint name="base_joint" type="fixed"> <parent link="base_footprint"/> <child link="base_link"/> <origin xyz="0.0 0.0 ${car_height/2 + distance}"/> </joint> <!-- 4、左前轮 --> <!-- 4-1、左前轮转动杆 --> <link name="fr_left_steer_link"> <inertial> <mass value="${steering_mass}" /> <inertia ixx="${steering_mass/12*(3*wheel_radius*wheel_radius + wheel_length*wheel_length)}" ixy="0" ixz="0" iyy="${steering_mass/12*(3*wheel_radius*wheel_radius + wheel_length*wheel_length)}" iyz="0" izz="${steering_mass/2 * wheel_radius*wheel_radius}" /> </inertial> </link> <!-- 4-2、将转动连杆与车体连接 --> <joint name="fr_left_steer_joint" type="revolute"> <origin xyz="${wheel_joint_x} ${wheel_joint_y} 0" rpy="0 0 0" /> <parent link="base_link" /> <child link="fr_left_steer_link" /> <axis xyz="0 0 1" /> <limit upper="0.6" lower="-0.6" effort="-1.0" velocity="-1.0" /> </joint> <!-- 4-3、设置左前车轮 --> <link name="fr_left_wheel"> <visual> <origin xyz="0 0 0" rpy="1.5707963 0 0" /> <geometry> <cylinder radius="${wheel_radius}" length = "${wheel_length}"/> </geometry> <material name="black"/> </visual> <!-- 4-4 设置碰撞参数 --> <collision> <origin xyz="0 0 0" rpy="1.5707963 0 0" /> <geometry> <cylinder radius="${wheel_radius}" length = "${wheel_length}"/> </geometry> </collision> <!-- 4-5 设置惯性矩阵 --> <inertial> <mass value="${wheel_mass}" /> <inertia ixx="${wheel_mass/12*(3*wheel_radius*wheel_radius + wheel_length*wheel_length)}" ixy="0" ixz="0" iyy="${wheel_mass/12*(3*wheel_radius*wheel_radius + wheel_length*wheel_length)}" iyz="0" izz="${wheel_mass/2 * wheel_radius*wheel_radius}" /> </inertial> </link> <!-- 4-6、gazebo有自己的颜色设置标签 --> <gazebo reference="fr_left_wheel"> <material>Gazebo/Black</material> </gazebo> <!-- 4-7、与转动连杆连接起来 --> <joint name="fr_left_wheel_joint" type="continuous"> <origin xyz="0 0 ${wheel_joint_z}" /> <parent link="fr_left_steer_link" /> <child link="fr_left_wheel" /> <axis xyz="0 0 -1" /> <dynamics friction="0.8" damping="0.5" /> <limit lower="-3.14159" upper="3.14159" effort="200" velocity="-1" /> </joint> <!-- 5、右前轮 --> <!-- 5-1、右前轮转动杆 --> <link name="fr_right_steer_link"> <inertial> <mass value="${steering_mass}" /> <inertia ixx="${steering_mass/12*(3*wheel_radius*wheel_radius + wheel_length*wheel_length)}" ixy="0" ixz="0" iyy="${steering_mass/12*(3*wheel_radius*wheel_radius + wheel_length*wheel_length)}" iyz="0" izz="${steering_mass/2 * wheel_radius*wheel_radius}" /> </inertial> </link> <!-- 5-2、将转动连杆与车体连接 --> <joint name="fr_right_steer_joint" type="revolute"> <origin xyz="${wheel_joint_x} -${wheel_joint_y} 0" rpy="0 0 0" /> <parent link="base_link" /> <child link="fr_right_steer_link" /> <axis xyz="0 0 1" /> <limit upper="0.6" lower="-0.6" effort="-1.0" velocity="-1.0" /> </joint> <!-- 5-3、设置右前车轮 --> <link name="fr_right_wheel"> <visual> <origin xyz="0 0 0" rpy="1.5707963 0 0" /> <geometry> <cylinder radius="${wheel_radius}" length = "${wheel_length}"/> </geometry> <material name="black"/> </visual> <!-- 5-4 设置碰撞参数 --> <collision> <origin xyz="0 0 0" rpy="1.5707963 0 0" /> <geometry> <cylinder radius="${wheel_radius}" length = "${wheel_length}"/> </geometry> </collision> <!-- 5-5 设置惯性矩阵 --> <inertial> <mass value="${wheel_mass}" /> <inertia ixx="${wheel_mass/12*(3*wheel_radius*wheel_radius + wheel_length*wheel_length)}" ixy="0" ixz="0" iyy="${wheel_mass/12*(3*wheel_radius*wheel_radius + wheel_length*wheel_length)}" iyz="0" izz="${wheel_mass/2 * wheel_radius*wheel_radius}" /> </inertial> </link> <!-- 5-6、gazebo有自己的颜色设置标签 --> <gazebo reference="fr_right_wheel"> <material>Gazebo/Black</material> </gazebo> <!-- 5-7、与转动连杆连接起来 --> <joint name="fr_right_wheel_joint" type="continuous"> <origin xyz="0 0 ${wheel_joint_z}" /> <parent link="fr_right_steer_link" /> <child link="fr_right_wheel" /> <axis xyz="0 0 1" /> <dynamics friction="0.8" damping="0.5" /> <limit lower="-3.14159" upper="3.14159" effort="200" velocity="-1" /> </joint> <!-- 6、左后轮 --> <!-- 6-1、设置左后车轮 --> <link name="re_left_wheel"> <visual> <origin xyz="0 0 0" rpy="1.5707963 0 0" /> <geometry> <cylinder radius="${wheel_radius}" length = "${wheel_length}"/> </geometry> <material name="black"/> </visual> <!-- 6-2 设置碰撞参数 --> <collision> <origin xyz="0 0 0" rpy="1.5707963 0 0" /> <geometry> <cylinder radius="${wheel_radius}" length = "${wheel_length}"/> </geometry> </collision> <!-- 6-3 设置惯性矩阵 --> <inertial> <mass value="${wheel_mass}" /> <inertia ixx="${wheel_mass/12*(3*wheel_radius*wheel_radius + wheel_length*wheel_length)}" ixy="0" ixz="0" iyy="${wheel_mass/12*(3*wheel_radius*wheel_radius + wheel_length*wheel_length)}" iyz="0" izz="${wheel_mass/2 * wheel_radius*wheel_radius}" /> </inertial> </link> <!-- 6-4、gazebo有自己的颜色设置标签 --> <gazebo reference="re_left_wheel"> <material>Gazebo/Black</material> </gazebo> <!-- 6-5、与车体连接起来 --> <joint name="re_left_wheel_joint" type="continuous"> <origin xyz="-${wheel_joint_x} ${wheel_joint_y} ${wheel_joint_z}" /> <parent link="base_link" /> <child link="re_left_wheel" /> <axis xyz="0 0 1" /> <dynamics friction="0.8" damping="0.5" /> <limit lower="-3.14159" upper="3.14159" effort="200" velocity="-1" /> </joint> <!-- 7、右后轮 --> <!-- 7-1、设置右后车轮 --> <link name="re_right_wheel"> <visual> <origin xyz="0 0 0" rpy="1.5707963 0 0" /> <geometry> <cylinder radius="${wheel_radius}" length = "${wheel_length}"/> </geometry> <material name="black"/> </visual> <!-- 7-2 设置碰撞参数 --> <collision> <origin xyz="0 0 0" rpy="1.5707963 0 0" /> <geometry> <cylinder radius="${wheel_radius}" length = "${wheel_length}"/> </geometry> </collision> <!-- 7-3 设置惯性矩阵 --> <inertial> <mass value="${wheel_mass}" /> <inertia ixx="${wheel_mass/12*(3*wheel_radius*wheel_radius + wheel_length*wheel_length)}" ixy="0" ixz="0" iyy="${wheel_mass/12*(3*wheel_radius*wheel_radius + wheel_length*wheel_length)}" iyz="0" izz="${wheel_mass/2 * wheel_radius*wheel_radius}" /> </inertial> </link> <!-- 7-4、gazebo有自己的颜色设置标签 --> <gazebo reference="re_right_wheel"> <material>Gazebo/Black</material> </gazebo> <!-- 7-5、与车体连接起来 --> <joint name="re_right_wheel_joint" type="continuous"> <origin xyz="-${wheel_joint_x} -${wheel_joint_y} ${wheel_joint_z}" /> <parent link="base_link" /> <child link="re_right_wheel" /> <axis xyz="0 0 1" /> <dynamics friction="0.8" damping="0.5" /> <limit lower="-3.14159" upper="3.14159" effort="200" velocity="-1" /> </joint> <!-- 8、虚拟方向盘 --> <link name="virtual_steer_link"> <visual> <origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" /> <geometry> <box size="0.01 0.01 0.01" /> </geometry> <material name="steer"> <color rgba="1.0 1.0 0.0 1" /> </material> </visual> <inertial> <!-- Gazebo won't show this link without this inertial mass --> <origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" /> <mass value="0.001" /> <inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0" /> </inertial> </link> <joint name="virtual_steering_wheel_joint" type="revolute"> <origin xyz="-${wheel_joint_x} 0.0 0.0" rpy="0.0 0.0 0.0" /> <parent link="base_link" /> <child link="virtual_steer_link" /> <axis xyz="-1 0 0" /> <limit lower="-3" upper="3" effort="200" velocity="20" /> </joint> <!-- 给上面的一些属性添加物理因素 --> <gazebo reference="base_link"> <material>Gazebo/White</material> <mu1>0.5</mu1> <!-- 静摩擦系数 --> <mu2>0.5</mu2> <!-- 滑动摩擦系数 --> </gazebo> <gazebo reference="fr_left_wheel"> <material>Gazebo/Black</material> <mu1>1.0</mu1> <mu2>1.0</mu2> </gazebo> <gazebo reference="fr_right_wheel"> <material>Gazebo/Black</material> <mu1>1.0</mu1> <mu2>1.0</mu2> </gazebo> <gazebo reference="re_left_wheel"> <material>Gazebo/Black</material> <mu1>1.0</mu1> <mu2>1.0</mu2> </gazebo> <gazebo reference="re_right_wheel"> <material>Gazebo/Black</material> <mu1>1.0</mu1> <mu2>1.0</mu2> </gazebo> <!-- 虚拟方向盘 --> <gazebo reference="virtual_steer_link"> <material>Gazebo/Yellow</material> </gazebo> <!-- 发布机器人的关节状态 (joint_states),并通过 ROS 2 系统与机器人状态发布器 (robot_state_publisher) --> <!-- Here's an example message to publish to test it: ros2 topic pub -1 /set_joint_trajectory trajectory_msgs/msg/JointTrajectory '{header: {frame_id: world}, joint_names: [slider_joint, arm_joint], points: [ {positions: {0.8,0.6}} ]}' --> <gazebo> <plugin name="gazebo_ros_joint_state_publisher" filename="libgazebo_ros_joint_state_publisher.so"> <update_rate>100</update_rate> <joint_name>fr_right_steer_joint</joint_name> <joint_name>fr_right_wheel_joint</joint_name> <joint_name>fr_left_steer_joint</joint_name> <joint_name>fr_left_wheel_joint</joint_name> <joint_name>re_right_wheel_joint</joint_name> <joint_name>re_left_wheel_joint</joint_name> <joint_name>virtual_steering_wheel_joint</joint_name> </plugin> </gazebo> <!-- 插件从 ROS 话题 /set_joint_trajectory 接收 JointTrajectory 消息并控制机器人关节运动。 --> <gazebo> <plugin name="gazebo_ros_joint_pose_trajectory" filename="libgazebo_ros_joint_pose_trajectory.so"> <update_rate>2</update_rate> </plugin> </gazebo> <!-- 阿克曼Gazebo插件 --> <gazebo> <plugin name='gazebo_ackermann_drive' filename='libgazebo_ros_ackermann_drive.so'> <ros> <!-- <namespace>ugv_gazebo_ackermann</namespace> --> <remapping>cmd_vel:=cmd_vel</remapping> <remapping>odom:=odom</remapping> <remapping>distance:=distance</remapping> </ros> <update_rate>100.0</update_rate> <!-- wheels --> <front_left_joint>fr_left_wheel_joint</front_left_joint> <front_right_joint>fr_right_wheel_joint</front_right_joint> <rear_left_joint>re_left_wheel_joint</rear_left_joint> <rear_right_joint>re_right_wheel_joint</rear_right_joint> <left_steering_joint>fr_left_steer_joint</left_steering_joint> <!-- <right_steering_joint>fr_right_steer_joint</right_steering_joint> --> <steering_wheel_joint>virtual_steering_wheel_joint</steering_wheel_joint> <!-- 车轮最大转向角 --> <max_steer>0.383972</max_steer> <!-- 方向盘最大转向角 --> <max_steering_angle>1.570796</max_steering_angle> <!-- 车辆最大线速度 m/s --> <max_speed>5</max_speed> <!-- PID 参数 --> <left_steering_pid_gain>1500 0 1</left_steering_pid_gain> <left_steering_i_range>0 0</left_steering_i_range> <right_steering_pid_gain>1500 0 1</right_steering_pid_gain> <right_steering_i_range>0 0</right_steering_i_range> <linear_velocity_pid_gain>1500 0 1</linear_velocity_pid_gain> <linear_velocity_i_range>0 0</linear_velocity_i_range> <!-- output --> <publish_odom>true</publish_odom> <publish_odom_tf>true</publish_odom_tf> <!-- Don't pubslish this when using robot localization --> <publish_wheel_tf>false</publish_wheel_tf> <!-- Don't publish this. It will override all wheel frames to robot_base_frame parameter below.--> <publish_distance>true</publish_distance> <odometry_frame>odom</odometry_frame> <robot_base_frame>base_footprint</robot_base_frame> </plugin> </gazebo>
</robot>
-
@2761607729 看看有没有什么插件报错,不行可以用ros2-control
-
@小鱼 插件没有报错,这也是从github上面搬下来的,我自己又重写了一个,感觉像逻辑问题,但是搞了好久也没找见是那个问题