0.参考
wiki HUSKY 官网 git HUSKY HUSKY_gazebo_Tutorials 代码资源
husky_base:与板载MCU通信硬件驱动程序; husky_bringup:调出启动文件和脚本; husky_control:控件配置; husky_description:机器人说明(URDF) husky_gazebo:Gazebo插件定义和机器人URDF的扩展; husky_msgs:消息定义 ; husky_navigation:导航配置及演示; husky_viz:可视化(rviz)配置和启动 。
1.下载源码
mkdir Husky_ws/src cd Husky_ws/src #下载指定分支HUSKY git clone -b melodic-devel https://github.com/husky/husky.git cd .. catkin_make
source devel/setup.bash # Set an environmental variable HUSKY_GAZEBO_DESCRIPTION: export HUSKY_URDF_EXTRAS=$(rospack find husky_description)/urdf/empty.urdf
2启动节点
roslaunch husky_gazebo husky_empty_world.launch roslaunch husky_gazebo husky_playpen.launch #
自定义环境 roslaunch husky_gazebo husky_empty_world.launch world_name:=worlds/willowgarage.world
3 键盘直接发布cmd_vel话题
rosrun turtlesim turtle_teleop_key turtle1/cmd_vel:=/cmd_vel
4添加模型
修改urdf文件,深度相机,3D文件中有雷达和单线雷达,文件可以直接修改。
修改 /Husky_ws/src/husky-melodic-devel/husky_description/urdf/husky.urdf.xacro文件
<?xml version="1.0"?> <!-- Software License Agreement (BSD) \file husky.urdf.xacro \authors Paul Bovbel <pbovbel@clearpathrobotics.com>, Devon Ash <dash@clearpathrobotics.com> \copyright Copyright (c) 2015, Clearpath Robotics, Inc., All rights reserved. Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met: * Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. * Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. * Neither the name of Clearpath Robotics nor the names of its contributors may be used to endorse or promote products derived from this software without specific prior written permission. THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WAR- RANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, IN- DIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUETIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT
OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
-->
<robot name="husky" xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:arg name="laser_enabled" default="$(optenv HUSKY_LMS1XX_ENABLED 0)" />
<xacro:arg name="laser_xyz" default="$(optenv HUSKY_LMS1XX_XYZ 0.2206 0.0 0.00635)" />
<xacro:arg name="laser_rpy" default="$(optenv HUSKY_LMS1XX_RPY 0.0 0.0 0.0)" />
<xacro:arg name="laser_secondary_enabled" default="$(optenv HUSKY_LMS1XX_SECONDARY_ENABLED 0)" />
<xacro:arg name="laser_secondary_xyz" default="$(optenv HUSKY_LMS1XX_SECONDARY_XYZ -0.2206 0.0 0.00635)" />
<xacro:arg name="laser_secondary_rpy" default="$(optenv HUSKY_LMS1XX_SECONDARY_RPY 0.0 0.0 3.14159)" />
<xacro:arg name="laser_ust10_front_enabled" default="$(optenv HUSKY_UST10_ENABLED 1)" />
<xacro:arg name="laser_ust10_front_prefix" default="$(optenv HUSKY_UST10_PREFIX front)" />
<xacro:arg name="laser_ust10_front_parent" default="$(optenv HUSKY_UST10_PARENT top_plate_link)" />
<xacro:arg name="laser_ust10_front_topic" default="$(optenv HUSKY_UST10_TOPIC front/scan)" />
<xacro:arg name="laser_ust10_front_xyz" default="$(optenv HUSKY_UST10_XYZ 0.2206 0.0 0.00635)" />
<xacro:arg name="laser_ust10_front_rpy" default="$(optenv HUSKY_UST10_RPY 0 0 0)" />
<xacro:arg name="laser_ust10_rear_enabled" default="$(optenv HUSKY_UST10_SECONDARY_ENABLED 0)" />
<xacro:arg name="laser_ust10_rear_prefix" default="$(optenv HUSKY_UST10_SECONDARY_PREFIX rear)" />
<xacro:arg name="laser_ust10_rear_parent" default="$(optenv HUSKY_UST10_SECONDARY_PARENT top_plate_link)" />
<xacro:arg name="laser_ust10_rear_topic" default="$(optenv HUSKY_UST10_SECONDARY_TOPIC rear/scan)" />
<xacro:arg name="laser_ust10_rear_xyz" default="$(optenv HUSKY_UST10_SECONDARY_XYZ -0.2206 0.0 0.00635)" />
<xacro:arg name="laser_ust10_rear_rpy" default="$(optenv HUSKY_UST10_SECONDARY_RPY 0 0 3.14159)" />
<xacro:arg name="laser_3d_enabled" default="$(optenv HUSKY_LASER_3D_ENABLED 1)" />
<xacro:arg name="laser_3d_xyz" default="$(optenv HUSKY_LASER_3D_XYZ 0 0 0)" />
<xacro:arg name="laser_3d_rpy" default="$(optenv HUSKY_LASER_3D_RPY 0 0 0)" />
<xacro:arg name="realsense_enabled" default="$(optenv HUSKY_REALSENSE_ENABLED 1)" />
<xacro:arg name="realsense_xyz" default="$(optenv HUSKY_REALSENSE_XYZ 0 0 0)" />
<xacro:arg name="realsense_rpy" default="$(optenv HUSKY_REALSENSE_RPY 0 0 0)" />
<xacro:arg name="realsense_mount" default="$(optenv HUSKY_REALSENSE_MOUNT_FRAME sensor_arch_mount_link)" />
<xacro:property name="husky_front_bumper_extend" value="$(optenv HUSKY_FRONT_BUMPER_EXTEND 0)" />
<xacro:property name="husky_rear_bumper_extend" value="$(optenv HUSKY_REAR_BUMPER_EXTEND 0)" />
<!-- Height of the sensor arch in mm. Must be either 510 or 300 -->
<xacro:arg name="sensor_arch_height" default="$(optenv HUSKY_SENSOR_ARCH_HEIGHT 510)" />
<xacro:arg name="sensor_arch" default="$(optenv HUSKY_SENSOR_ARCH 0)" />
<xacro:arg name="robot_namespace" default="$(optenv ROBOT_NAMESPACE /)" />
<xacro:arg name="urdf_extras" default="$(optenv HUSKY_URDF_EXTRAS empty.urdf)" />
<xacro:arg name="cpr_urdf_extras" default="$(optenv CPR_URDF_EXTRAS empty.urdf)" />
<!-- Included URDF/XACRO Files -->
<xacro:include filename="$(find husky_description)/urdf/decorations.urdf.xacro" />
<xacro:include filename="$(find husky_description)/urdf/wheel.urdf.xacro" />
<xacro:include filename="$(find husky_description)/urdf/accessories/intel_realsense.urdf.xacro"/>
<xacro:include filename="$(find husky_description)/urdf/accessories/sick_lms1xx_mount.urdf.xacro"/>
<xacro:include filename="$(find husky_description)/urdf/accessories/sensor_arch.urdf.xacro"/>
<xacro:include filename="$(find husky_description)/urdf/accessories/hokuyo_ust10.urdf.xacro"/>
<xacro:include filename="$(find husky_description)/urdf/accessories/vlp16_mount.urdf.xacro"/>
<xacro:include filename="$(find husky_description)/urdf/accessories/hdl-32e_mount.urdf.xacro"/>
<xacro:property name="M_PI" value="3.14159"/>
<!-- Base Size -->
<xacro:property name="base_x_size" value="0.98740000" />
<xacro:property name="base_y_size" value="0.57090000" />
<xacro:property name="base_z_size" value="0.24750000" />
<!-- Wheel Mounting Positions -->
<xacro:property name="wheelbase" value="0.5120" />
<xacro:property name="track" value="0.5708" />
<xacro:property name="wheel_vertical_offset" value="0.03282" />
<!-- Wheel Properties -->
<xacro:property name="wheel_length" value="0.1143" />
<xacro:property name="wheel_radius" value="0.1651" />
<!-- Base link is the center of the robot's bottom plate --> <link name="base_link"> <visual> <origin xyz="0 0 0" rpy="0 0 0" /> <geometry> <mesh filename="package://husky_description/meshes/base_link.dae" /> </geometry> </visual> <collision> <origin xyz="${( husky_front_bumper_extend - husky_rear_bumper_extend ) / 2.0} 0 ${base_z_size/4}" rpy="0 0 0" /> <geometry> <box size="${ base_x_size + husky_front_bumper_extend + husky_rear_bumper_extend } ${base_y_size} ${base_z_size/2}"/> </geometry> </collision> <collision> <origin xyz="0 0 ${base_z_size*3/4-0.01}" rpy="0 0 0" /> <geometry> <box size="${base_x_size*4/5} ${base_y_size} ${base_z_size/2-0.02}"/> </geometry> </collision> </link> <!-- Base footprint is on the ground under the robot --> <link name="base_footprint"/> <joint name="base_footprint_joint" type="fixed"> <origin xyz="0 0 ${wheel_vertical_offset - wheel_radius}" rpy="0 0 0" /> <parent link="base_link" /> <child link="base_footprint" /> </joint> <!-- Inertial link stores the robot's inertial information -->
<link name="inertial_link">
<inertial>
<mass value="46.034" />
<origin xyz="-0.00065 -0.085 0.062" />
<inertia ixx="0.6022" ixy="-0.02364" ixz="-0.1197" iyy="1.7386" iyz="-0.001544" izz="2.0296" />
</inertial>
</link>
<joint name="inertial_joint" type="fixed">
<origin xyz="0 0 0" rpy="0 0 0" />
<parent link="base_link" />
<child link="inertial_link" />
</joint>
<!-- IMU Link is the standard mounting position for the UM6 IMU.-->
<!-- Can be modified with environment variables in /etc/ros/setup.bash -->
<link name="imu_link"/>
<joint name="imu_joint" type="fixed">
<origin xyz="$(optenv HUSKY_IMU_XYZ 0.19 0 0.149)" rpy="$(optenv HUSKY_IMU_RPY 0 -1.5708 3.1416)" />
<parent link="base_link" />
<child link="imu_link" />
</joint>
<gazebo reference="imu_link">
</gazebo>
<!-- Husky wheel macros -->
<xacro:husky_wheel wheel_prefix="front_left">
<origin xyz="${wheelbase/2} ${track/2} ${wheel_vertical_offset}" rpy="0 0 0" />
</xacro:husky_wheel>
<xacro:husky_wheel wheel_prefix="front_right">
<origin xyz="${wheelbase/2} ${-track/2} ${wheel_vertical_offset}" rpy="0 0 0" />
</xacro:husky_wheel>
<xacro:husky_wheel wheel_prefix="rear_left">
<origin xyz="${-wheelbase/2} ${track/2} ${wheel_vertical_offset}" rpy="0 0 0" />
</xacro:husky_wheel>
<xacro:husky_wheel wheel_prefix="rear_right">
<origin xyz="${-wheelbase/2} ${-track/2} ${wheel_vertical_offset}" rpy="0 0 0" />
</xacro:husky_wheel>
<xacro:husky_decorate />
<!--
Add the primary and secondary lasers
-->
<xacro:if value="$(arg laser_enabled)">
<xacro:sick_lms1xx_mount prefix="base"/>
<xacro:sick_lms1xx frame="base_laser" topic="scan" robot_namespace="$(arg robot_namespace)"/>
<joint name="laser_mount_joint" type="fixed">
<origin xyz="$(arg laser_xyz)" rpy="$(arg laser_rpy)" />
<parent link="top_plate_link" />
<child link="base_laser_mount" />
</joint>
</xacro:if>
<xacro:if value="$(arg laser_secondary_enabled)">
<xacro:sick_lms1xx_mount prefix="rear"/>
<xacro:sick_lms1xx frame="rear_laser" topic="rear/scan" robot_namespace="$(arg robot_namespace)"/>
<joint name="laser_secondary_mount_joint" type="fixed">
<origin xyz="$(arg laser_secondary_xyz)" rpy="$(arg laser_secondary_rpy)" />
<parent link="top_plate_link" />
<child link="rear_laser_mount" />
</joint>
</xacro:if>
<!--
Add front and back hokuyo UST10 Lidars
-->
<xacro:if value="$(arg laser_ust10_front_enabled)">
<xacro:hokuyo_ust10_mount topic="$(arg laser_ust10_front_topic)" prefix="$(arg laser_ust10_front_prefix)" parent_link="$(arg laser_ust10_front_parent)">
<origin xyz="$(arg laser_ust10_front_xyz)" rpy="$(arg laser_ust10_front_rpy)" />
</xacro:hokuyo_ust10_mount>
</xacro:if>
<xacro:if value="$(arg laser_ust10_rear_enabled)">
<xacro:hokuyo_ust10_mount topic="$(arg laser_ust10_rear_topic)" prefix="$(arg laser_ust10_rear_prefix)" parent_link="$(arg laser_ust10_rear_parent)">
<origin xyz="$(arg laser_ust10_rear_xyz)" rpy="$(arg laser_ust10_rear_rpy)" />
</xacro:hokuyo_ust10_mount>
</xacro:if>
<!--
Add the main sensor arch if the user has specifically enabled it, or if a sensor
requires it for mounting
-->
<xacro:property name="sensorbar_user_enabled" value="$(arg sensor_arch)" />
<xacro:property name="sensorbar_needed_realsense" value="$(arg realsense_enabled)" />
<xacro:property name="sensorbar_needed_lidar" value="$(arg laser_3d_enabled)" />
<xacro:if value="${sensorbar_needed_realsense or sensorbar_user_enabled or sensorbar_needed_lidar}">
<xacro:sensor_arch prefix="" parent="top_plate_link" size="$(arg sensor_arch_height)">
<origin xyz="$(optenv HUSKY_SENSOR_ARCH_OFFSET 0 0 0)" rpy="$(optenv HUSKY_SENSOR_ARCH_RPY 0 0 0)"/>
</xacro:sensor_arch>
</xacro:if>
<!-- add the intel realsense to the sensor arch if needed -->
<xacro:if value="$(arg realsense_enabled)">
<link name="realsense_mountpoint"/>
<joint name="realsense_mountpoint_joint" type="fixed">
<origin xyz="$(arg realsense_xyz)" rpy="$(arg realsense_rpy)" />
<parent link="$(arg realsense_mount)"/>
<child link="realsense_mountpoint" />
</joint>
<xacro:intel_realsense_mount prefix="camera" topic="realsense" parent_link="realsense_mountpoint"/>
</xacro:if>
<!--
Add the 3d laser to the sensor arch if needed
-->
<xacro:if value="$(arg laser_3d_enabled)">
<!-- <xacro:vlp16_mount prefix="" parent_link="sensor_arch_mount_link" topic="$(optenv HUSKY_LASER_3D_TOPIC points)">
<origin xyz="$(arg laser_3d_xyz)" rpy="$(arg laser_3d_rpy)" />
</xacro:vlp16_mount> -->
<xacro:hdl32e_mount prefix="" parent_link="sensor_arch_mount_link" topic="$(optenv HUSKY_LASER_3D_TOPIC points)">
<origin xyz="$(arg laser_3d_xyz)" rpy="$(arg laser_3d_rpy)" />
</xacro:hdl32e_mount>
</xacro:if>
<gazebo>
<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
<robotNamespace>$(arg robot_namespace)</robotNamespace>
<legacyModeNS>true</legacyModeNS>
</plugin>
</gazebo>
<gazebo