Note: This tutorial assumes you already completed the getting started tutorial.
(!) 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.

Creating a full robot in NXT-ROS

Description: This tutorial shos you how to create an nxt_ros.yaml file for you nxt robot and launch it to view the data.

Tutorial Level: BEGINNER

Next Tutorial: Creating a simple robot model using lxf2urdf.py

Connect Sensors

For this tutorial, let's add some more sensors and motors: plug in a touch sensor, a color sensor, an ultrasonic sensor, and a servo motor.

  • PORT1: intensity sensor
  • PORT2: ultrasonic sensor
  • PORT3: touch sensor
  • PORTA: servo

Create robot.yaml

The yaml file

First, create learning_nxt/robot.yaml in your favorite editor, and place the following inside it:

   1 nxt_robot:
   2   - type: motor
   3     name: l_motor_joint
   4     port: PORT_A
   5     desired_frequency: 10.0
   6   - type: touch
   7     frame_id: r_touch_link
   8     name: touch_sensor
   9     port: PORT_3
  10     desired_frequency: 10.0
  11   - type: ultrasonic
  12     frame_id: r_ultrasonic_link
  13     name: ultrasonic_sensor
  14     port: PORT_2
  15     spread_angle: 0.2
  16     min_range: 0.01
  17     max_range: 2.5
  18     desired_frequency: 10.0
  19   - type: intensity
  20     frame_id: l_intensity_link
  21     name: intensity_sensor
  22     port: PORT_1
  23     color_r: 1.0
  24     color_g: 0.0
  25     color_b: 0.0
  26     desired_frequency: 10.0

The yaml explained

Now, let's break down the ymal piece by piece.

   1 nxt_robot:

Here we are putting everything in the nxt_robot namespace.

   2   - type: motor
   3     name: l_motor_joint
   4     port: PORT_A
   5     desired_frequency: 10.0

These lines creates a motor object with name L_motor_joint that are connected to PORT_A with a pulling frequency of 10Hz.

   6   - type: touch
   7     frame_id: r_touch_link
   8     name: touch_sensor
   9     port: PORT_3
  10     desired_frequency: 10.0

These lines creates a touch object with name touch_sensor and a frame_id r_touch_link of that is connected to PORT_3. The pulling frequency in this case is 10Hz.

  11   - type: ultrasonic
  12     frame_id: r_ultrasonic_link
  13     name: ultrasonic_sensor
  14     port: PORT_2
  15     spread_angle: 0.2
  16     min_range: 0.01
  17     max_range: 2.5
  18     desired_frequency: 10.0

These lines creates an ultrasonic sensor with a spread angle of 0.2m, a min range of 0.01m, and a max range of 2.5m that is connected to PORT_2.

  19   - type: intensity
  20     frame_id: l_intensity_link
  21     name: intensity_sensor
  22     port: PORT_1
  23     color_r: 1.0
  24     color_g: 0.0
  25     color_b: 0.0
  26     desired_frequency: 10.0

These lines creates a intensity object with name intensity_sensor and a frame_id l_intensity_link of that is connected to PORT_1 with the red LED on.

Launch the yaml File

Now we need to create a launch file to launch the robot.yaml file. Create learning_nxt/robot.launch in your favorite editor, and place the following inside it:

<launch>

  <node pkg="nxt_ros" type="nxt_ros.py" name="nxt_ros" output="screen" respawn="true">
    <rosparam command="load" file="$(find learning_nxt)/robot.yaml" />
  </node>

  <node pkg="nxt_ros" type="joint_states_aggregator.py" name="joint_state_publisher" output="screen" />

</launch>

Turn on your nxt brick and connect it to the computer via USB. Now roslaunch:

$ roslaunch robot.launch

You should see something similar to:

  • SUMMARY
    ========
    
    PARAMETERS
     * /nxt_ros/nxt_robot
    
    NODES
      /
        nxt_ros (nxt_ros/nxt_ros.py)
        joint_state_publisher (nxt_ros/joint_states_aggregator.py)
    
    starting new master (master configured for auto start)
    process[master]: started with pid [32451]
    ROS_MASTER_URI=http://bvo:11311/
    
    setting /run_id to 281dd58e-afb1-11df-98e9-00251148e8cf
    process[rosout-1]: started with pid [32464]
    started core service [/rosout]
    process[nxt_ros-3]: started with pid [32493]
    process[joint_state_publisher-4]: started with pid [32494]
    [INFO] 1282676127.009863: Creating motor with name l_motor_joint on PORT_A
    [INFO] 1282676127.016516: Creating touch with name touch_sensor on PORT_3
    [INFO] 1282676127.022412: Creating ultrasonic with name ultrasonic_sensor on PORT_2
    [INFO] 1282676127.127735: Creating intensity with name intensity_sensor on PORT_1

Viewing Data

Now you can list all the topics:

$ rostopic list 

Now you can see all the sensor and joint data:

  • /intensity_sensor
    /joint_command
    /joint_state
    /joint_states
    /rosout
    /touch_sensor
    /ultrasonic_sensor

You will see topics for each sensor and state/command topics for the joints in this case (motor1 and motor2).

Run:

$ rostopic echo joint_states

Wiki: nxt_ros/Tutorials/Creating a full robot (last edited 2013-06-10 09:27:09 by esteve)