Contents
leJOS ROS API
This package provides the leJOS ROS API. There is an alternate package - nxt_lejos_lcp_proxy - which provides a very similar API and does not need a responder running on the NXT, but this package is much faster, and is recommended.
Example
Even though the API description looks quite complicated, it's very easy to configure the bindings. Here is an example configuration:
nxt_robot: - type: motor name: r_wheel_joint port: PORT_A desired_frequency: 20.0 - type: motor name: l_wheel_joint port: PORT_B desired_frequency: 20.0 - type: gyro name: gyro frame_id: gyro_link port: PORT_3 offset: 0 desired_frequency: 20.0 - type: ultrasonic frame_id: ultrasonic_link name: ultrasonic_sensor port: PORT_2 desired_frequency: 10.0 - type: differential_pilot name: pilot port: PORT_AC desired_frequency: 10.0 track_width: 16.0 wheel_diameter: 5.6 reverse: true
Motor
leJOS ROS API for the NXT motorSubscribed Topics
~<name> (nxt_msgs/JointVelocity)- The joint velocity to apply at the joint
Published Topics
~joint_state (sensor_msgs/JointState)- The current power, position, and velocity of the servo motors.
Parameters
~nxt_robot/type (string, default: None)- The type should be set to "motor".
- This should be one of the brick ports: PORT_A, PORT_B or PORT_C.
- The desired update frequency for the actuator and sensor.
- The topic name for the sensor data.
Ultrasonic Sensor
leJOS ROS API for the ultrasonic sensorPublished Topics
~<name> (sensor_msgs/Range)Parameters
~nxt_robot/type (string, default: None)- The type should be set to "ultrasonic".
- This should be one of the brick ports: PORT_1, PORT_2, PORT_3, or PORT_4.
- The desired update frequency for the sensor.
- The topic name for the sensor data.
- The frame that the sensor data is published in.
Touch Sensor
leJOS ROS API for the touch sensorPublished Topics
~<name> (nxt_msgs/Contact)- The state of the touch sensor (touching or not).
Parameters
~nxt_robot/type (string, default: None)- The type should be set to "touch".
- This should be one of the brick ports: PORT_1, PORT_2, PORT_3, or PORT_4.
- The desired update frequency for the sensor.
- The topic name for the sensor data.
- The frame that the sensor data is published in.
Color Sensor
leJOS ROS API for the color sensorPublished Topics
~<name> (nxt_msgs/Color)- Color value measured from the color sensor.
Parameters
~nxt_robot/type (string, default: None)- The type should be set to "color".
- This should be one of the brick ports: PORT_1, PORT_2, PORT_3, or PORT_4.
- The desired update frequency for the sensor.
- The topic name for the sensor data.
- The frame that the sensor data is published in.
Gyro Sensor
leJOS ROS API for the gyro sensorPublished Topics
~<name> (nxt_msgs/Gyro)- Rotation rate data from the gyro sensor.
Parameters
~nxt_robot/type (string, default: None)- The type should be set to "gyro".
- This should be one of the brick ports: PORT_1, PORT_2, PORT_3, or PORT_4.
- The desired update frequency for the sensor.
- The topic name for the sensor data.
- The frame that the sensor data is published in.
Acceleration Sensor
leJOS ROS API for the acceleration sensorPublished Topics
~<name> (nxt_msgs/Accelerometer)- The three axis measured values form the accelerometer sensor.
Parameters
~nxt_robot/type (string, default: None)- The type should be set to "accelerometer".
- This should be one of the brick ports: PORT_1, PORT_2, PORT_3, or PORT_4.
- The desired update frequency for the sensor.
- The topic name for the sensor data.
- The frame that the sensor data is published in.
Light Sensor
leJOS ROS API for the light sensorPublished Topics
~<name> (nxt_msgs/Intensity)- Intensity value measured from the light sensor.
Parameters
~nxt_robot/type (string, default: None)- The type should be set to "light".
- This should be one of the brick ports: PORT_1, PORT_2, PORT_3, or PORT_4.
- The desired update frequency for the sensor.
- The topic name for the sensor data.
- The frame that the sensor data is published in.
Sound Sensor
leJOS ROS API for the intensity sensorPublished Topics
~<name> (nxt_lejos_msgs/Decibels)- Decibels measured from the sound sensor.
Parameters
~nxt_robot/type (string, default: None)- The type should be set to "sound".
- This should be one of the brick ports: PORT_1, PORT_2, PORT_3, or PORT_4.
- The desired update frequency for the sensor.
- The topic name for the sensor data.
- The frame that the sensor data is published in.
Compass Sensor
leJOS ROS API for the compass sensorPublished Topics
~<name> (nxt_lejos_msgs/Compass)- Heading value measured from the compass sensor.
Parameters
~nxt_robot/type (string, default: None)- The type should be set to "compass".
- This should be one of the brick ports: PORT_1, PORT_2, PORT_3, or PORT_4.
- The desired update frequency for the sensor.
- The topic name for the sensor data.
- The frame that the sensor data is published in.
Differential Pilot
leJOS ROS API for the differential pilotSubscribed Topics
~dns_command (nxt_lejos_msgs/DNSCommand)- Differential pilot commands.
- The desired linear and angular x,y,z of the base.
Published Topics
~tf (tf/tfMessage)- tf transforms
- odometry data
Parameters
~nxt_robot/type (string, default: None)- The type should be set to "differential_pilot".
- This should be one of the brick ports: PORT_AB, PORT_AC, or PORT_BC.
- The desired update frequency for the sensor.
- The topic name for the sensor data.
- The frame that the sensor data is published in.