(!) Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags.

Customize Husky Configuration

Description: Adding customizations to the base Husky robot configuration.

Keywords: Clearpath Husky

Tutorial Level: INTERMEDIATE

Note: These tutorials assume that you are familiar with ROS and the catkin build system. Please familiarize yourself using the ROS and catkin tutorials.

If upgrading from a prior ROS release, you should now re-examine your backed-up files from Backing Up Husky Configuration to determine if there's any customizations that need to be configured on your platform.

Environment Variables

Husky's standard peripherals can be configured using these environment variables, to be added to the robot-wide setup file (/etc/ros/setup.bash). These environment variables are loaded on boot.

Variable

Default

Description

ROBOT_NETWORK

None

Configure a network interface to trigger the husky-core job, and initialize ROS_IP. If not set, husky-core will define ROS_HOSTNAME instead (see Network Setup)

HUSKY_IMU_PORT

/dev/clearpath/imu

Port for the Husky UM6 IMU if present, must be set before running husky_bringup install

HUSKY_IMU_XYZ

0.19 0.0 0.149

Pose offset for the Husky IMU's standard mounting location

HUSKY_IMU_RPY

0.0 -1.5708 3.1416

Orientation offset for the Husky IMU's standard mounting location

HUSKY_NAVSAT_PORT

/dev/clearpath/gps

Port for the Husky GPS if present, must be set before running husky_bringup install

HUSKY_NAVSAT_BAUD

19200

Baudrate for the Husky GPS

HUSKY_UR5_IP

None

IP Address for the UR5 manipulator if present, must be set before running husky_bringup install

HUSKY_UR5_ENABLED

false

Enable/disable the UR5 manipulator.

HUSKY_LMS1XX_IP

None

IP Address for the SICK LMS1XX LIDAR if present, must be set before running husky_bringup install

HUSKY_LMS1XX_ENABLED

false

Enable/disable the SICK LMS1XX LIDAR

HUSKY_LMS1XX_XYZ

0.2206 0.0 0.00635

Pose offset for the SICK LMS1XX LIDAR

HUSKY_LMS1XX_RPY

0.0 0.0 0.0

Orientation offset for the SICK LMS1XX LIDAR

HUSKY_TOP_PLATE_ENABLED

true

Enable/disable the standard Husky top plate.

FLIR_PTU_PENABLED

false

Enable for a FLIR PTU to be added to the Dual UR5 arm husky configuration. Must have HUSKY_DUAL_UR5_ENABLED set to true for this to work.

HUSKY_DUAL_UR5_ENABLED

false

Enable to use the Dual UR5 arm husky configuration with bulk head. This will spawn the husky with 2 arms and prime it for use with MoveIt

ROBOTIQ_GRIPPERS_ENABLED

false

Enable to use the robotiq grippers for the dual UR5 arm huskies. This will put grippers on both left and right arms. DUAL UR5 Enabled must be set to true

HUSKY_LASER_ENABLED

true

Enable to use the default husky laser. This MUST be disabled to correctly use the DUAL UR5 husky build

HUSKY_LASER_PARENT_LINK

top_plate_link

Set this to change the parent of the LIDAR used on the Husky. Useful if you are using non-standard configurations. Set to bulkhead_link for dual ur5 config

HUSKY_KINECT_XYZ

xyz

Set this to be whatever xyz you want for the Husky kinect

HUSKY_KINECT_RPY

rpy

Set this to be whatever rpy you want for Husky kinect attachment

BUMBLEBEE_ENABLED

false

Set this to enable the bumblebee attachment onto the FLIR_PTU if flir PTU is enabled

VELODYNE_VLP16_ENABLED

false

Set this to enable the velodyne vlp 16 3d imaging system on the dual ur5 setup.

ROBOTIQ_FT_300_ENABLED

false

Set this to enable the robotiq ft 300's on each of the left and right ur5 arms when dual ur5 is enabled

Adding a source workspace

Configuring non-standard peripherals requires a source workspace on the robot PC.

  1. Create a new workspace:
     $ mkdir -p ~/husky_indigo_ws/src
  2. Add any custom source packages to the ~/husky_indigo_ws/src directory.

  3. After adding your packages, make sure any necessary dependencies are installed:
     $ cd ~/husky_indigo_ws/
     $ rosdep install --from-paths src --ignore-src --rosdistro indigo -y
  4. Build the workspace:
     $ cd ~/husky_indigo_ws/
     $ catkin_make
  5. Modify your robot-wide setup file (/etc/ros/setup.bash) to source your new workspace instead of the base indigo install:

     ...
     source /home/administrator/husky_indigo_ws/devel/setup.bash
  6. Reinitialize your environment so that it picks up your new workspace:
     $ source /etc/ros/setup.bash
  7. Augment the husky-core job with launch files from your custom packages:
     $ rosrun robot_upstart install my_custom_package/launch --job husky-core --augment

Robot Description

In ROS Hydro and earlier, custom Husky descriptions (URDFs) were provided to customers in a workspace in their home folder. Since the Husky URDF has undergone some changes for Indigo, your robot description from prior ROS releases will have to be slightly adapted.

To create a custom Husky configuration, fork the husky_customization repository to your GitHub account, and clone the fork into your workspace:

  • $ cd ~/husky_indigo_ws/src
    $ git clone https://github.com/<username>/husky_customization.git -b indigo-devel
    $ cd ~/husky_indigo_ws
    $ catkin_make
    $ source devel/setup.bash

To modify your Husky's URDF description (see ROS URDF Tutorials), edit the husky_customization/husky_custom_description/urdf/custom_description.urdf.xacro file. Run roslaunch husky_viz view_model.launch to see your custom model in rviz.

To modify your Husky's simulation configuration (see Gazebo's URDF Tutorials), edit the husky_customization/husky_custom_gazebo/urdf/custom_description.gazebo.xacro file. Run roslaunch husky_gazebo husky_playpen.launch to see your custom Gazebo configuration in action!

Once you are done customizing your Husky configuration, don't forget to commit and push the changes back into your GitHub repository.

Network Configuration

If upgrading from prior ROS releases, your old /etc/network/interfaces file may contain a static IP binding for your robot, or other customizations that should be replicated on your new setup.

Wiki: husky_bringup/Tutorials/Customize Husky Configuration (last edited 2022-11-17 10:28:22 by GavrielKrauss)