-
Notifications
You must be signed in to change notification settings - Fork 24
Basic Packages version 1.1
The computer in the model car contains preinstalled packages which can help you to develop your own code. They consist of sensor- and actuator nodes.

Figure 9: Basic ROS Packages preinstalled in the car.
The purpose of the packages should be apparent from their names. In the next sections we review each one of them.
rplidarNode is a driver for RPLIDAR. It reads RPLIDAR raw scan result using RPLIDAR's SDK and converts them to ROSLaserScan messages.
scan (sensor_msgs/LaserScan) it publishes scan topic from the laser
stop_motor(std_srvs/Empty)
start_motor (std_srvs/Empty)
serial_port (string,default: /dev/ttyUSB0) serial port name used in your system.
serial_baudrate (int, default: 115200) serial port baud rate.
frame_id (string, default: laser) frame ID for the device
inverted (bool, default: false) indicates if the LIDAR is mounted inverted.
angle_compensate (bool, default: true) indicates if the driver needs to do angle compensation.
Once you have changed the USB port remap, you can change the launch file with the serial_port value.
<param name="serial_port" type="string" value="/dev/rplidar"/>
Start a rplidarNode and view the scan result in using “rostopic echo scan”.
$ roslaunch rplidar_ros rplidar.launch
Serial is a cross-platform, simple to use library for using serial ports on computers. This library provides a C++, object oriented interface for interacting with RS-232 like devices on Linux and Windows.
send_steering_light Node sends desired steering angle and light command through serial port to Arduino. It reads the desired steering angle in integer and convert to string message.
It sends also specified strings through the serial port to the Arduino board in order to turn the lights on/off.
string Light
____________________________________________
le Blinking yellow left
ri Blinking yellow right
stop Turn on the three red tail lights (braking)
pa Turn on the two red back lights, and two white front lights
ta Turn on the two red back lights, and two white front lights
re Turn on the white lights at the back for going backwards.
fr Turn on the two white headlights for driving at night
diL Turnoff the lights
manual_control/steering (std_msgs/Int16) .
manual_control/lights (std_msgs/String)
serial_port (string,default: /dev/ttyUSB3) serial port name used in your system.
serial_baudrate (int, default: 115200) serial port baud rate.
Once you have changed the USB port remap, you can change the launch file about the serial_port value and baud rate.
Start a steering node and change the car’s steering angle.
$ roslaunch send_steering_light servo_light_odroid.launch
$ rostopic pub -r 1 /manual_control/steering std_msgs/Int16 '{data: 90}'
$ rostopic pub -r 1 /manual_control/lights std_msgs/String '{data: le}'
resolution=?!
motor_communication Node sends desired velocity through serial port to BLDC motor. It reads desired velocity in integer and convert to string message.
manual_control/speed (std_msgs/Int16) desired velocity.
serial_port (string,default: /dev/ttyUSB2) serial port name used in your system.
serial_baudrate (int, default: 9600) serial port baud rate.
Once you have changed the USB port remap, you can change the launch file about the serial_port value and baud rate.
<param name="motor_serial_port" value="/dev/ttyUSB" />
<param name="motor_baud_rate" value="115200" />
Start a motor_communication node and change motor speed.
$ roslaunch motor_communication motor_odroid.launch
$ rostopic pub -r 1 manual_control/speed std_msgs/Int16 '{data: 100}'
Maximum rpm is 12000, but 1000 rpm is also fast enough for the model car.
baudrate:?
Command Argument Function
_______________________________________________________________
en - Enable Drive
di - Disable Drive
v value Select Velocity Mode
gn - Get N: Current actual velocity in rpm
baud value Select baud rate (max: 115200)
POS - Get Actual Position
The usb_cam_node interfaces with standard USB cameras (e.g. the fish-eye camera) using libusb_cam and publishes images as sensor_msgs::Image. Uses the image_transport library to allow compressed image transport.
usb_cam/image_raw
The camera name. This must match the name in the camera calibration
~camera_name (string, default: head_camera)
You should use camera_calibration package of ROS to calibrate the camera for further use.
Start usb_cam node to publish the image_raw topic.
$ roslaunch usb_cam usb_cam-test.launch
to use the usb_cam ,
-
Put the usb_cam package inside your workspace
-
Delete the remapping line in the launch file (usb_cam/launch/usb_cam-test.launch) :
<remap from="usb_cam/image_raw" to="app/camera/rgb/image_raw" /> -
Find the port of USB (/dev/video?) of fish eye camera and modify the launch file based on:
<param name="video_device" value="/dev/video0" />
This package contains launch files for using the Intel RealSense camera device.
You should run realsense_sr300 node twice to start the intel sr300 camera.
$ roslaunch realsense_camera realsense_sr300.launch
make sure there is not any nodelet with the same name running on the odroid, to stop the nodelet you can find the id of nodelet using "pgrep nodelet" and then kill it "pkill nodelet" in the model car.
$ pkill nodelet
$ pkill rosmaster
This node is used to localize the car using at least two colored markers attached to the ceiling. The fisheye camera on top of the car provides an angle of view of 170 degrees. It can be used to detect, for example, color lamps mounted from the ceiling. To use the package, follow the calibration and running steps described below. Calibration Steps First connect the camera to your laptop and find the camera matrix and calibrate camera with the calibrate_camera package in ROS1. To calibrate the camera, you need a chess board. Make sure that you fasten the chess paper to a smooth and firm (inelastic) surface, such as a piece of wood. Save the .ros/camera_info/head_camera.yaml file which contains intrinsic and extrinsic camera parameters, and copy the file to the Odroid.
$ roslaunch usb_cam usb_cam-test.launch
$ rosrun camera_calibration cameracalibrator.py --size 8x6 --square 0.108 image:=/usb_cam/image_raw camera:=/usb_cam

Figure 10: Calibrate the camera with a chess board
Figure 11: camera picture before and after calibration
image_width: 640
image_height: 480
camera_name: head_camera
camera_matrix:
rows: 3
cols: 3
data: [373.4585526709734, 0, 344.7922479586828, 0, 374.208011913253, 207.9995810706301, 0, 0, 1]
distortion_model: plumb_bob
distortion_coefficients:
rows: 1
cols: 5
data: [-0.3025934119216705, 0.06682905008576441, -0.002063818675390365, 0.001507299697649222, 0]
rectification_matrix:
rows: 3
cols: 3
data: [1, 0, 0, 0, 1, 0, 0, 0, 1]
projection_matrix:
rows: 3
cols: 4
data: [267.5132141113281, 0, 358.2688813130517, 0, 0, 309.1231689453125, 191.8470852238897, 0, 0, 0, 1, 0]
File 1: Camera fish-eye parameters (.ros/camera_info/head_camera.yaml)
To test the calibration you can run the nodes below in a launch file:
<node name="image_proc" pkg="image_proc" type="image_proc" ns="usb_cam" required="true" output="screen">
<node name="image_view" pkg="image_view" type="image_view" respawn="false" output="screen">
<remap from="image" to="/usb_cam/image_rect_color"/>
<param name="autosize" value="true" />
</node>
In the second step, you should find the color range of each lamp in order to detect them. Minimizing exposure helps the color detection to be independent from environment lights. Minimize camera exposure using v4l_ctrl as shown below:
$ v4l2-ctl --device=/dev/video1 --list-ctrls
$ v4l2-ctl --device=/dev/video0 --set-ctrl exposure_auto=1
$ v4l2-ctl --device=/dev/video0 --set-ctrl exposure_absolute=1
Run colorgui node from cm_vision package, to find the range of colors of markers2.
$roslaunch cmvision 1.launch

Figure 12: colorgui node, copy RGB and YUV number after clicking on a marker. Click on a color lamp, click several times on it to find the color range of the lamp, save RGB and YUV of each color in color.txt file. Close the node and run it for the next lamp (color). Save red, green, blue, purple colors number alternatively in the color.txt. Copy the color.txt file inside the visual_gps/config/FEATURE_FILES/ folder in the Odroid.
In the third step, find the position of the lamps respect to the known origin in the room. Save red, green, blue, purple colors lamps position alternatively in map.txt file. Copy the map.txt file inside the visual_gps /config/FEATURE_FILES folder.
Now you can run visual_gps launch file from visual_gps package to localize the car. The launch file run following nodes:
- usb_cam and image_proc (to read calibrated image)
- cmvision node (to find the calibrated markers)
- detect_roof_rectangles (to filter the blobs and find the biggest)
- visual_gps (to find the transformation between map and position of camera which defines the location of camera/car)
For test the node, run the package in your PC, use Rviz to visualize your position.
$roslaunch visual_gps visual_gps_2d_rviz.launch

Figure 13: The model car position respect to world frame in RViZ using visual_gps_2d node
This node used to read the yaw angle through the serial port from Arduino.
model_car/yaw (std_msgs/Float32)
serial_port (string,default: /dev/ttyUSB3)
serial_baudrate (int, default: 115200)
Start a heading node and subscribe to the yaw angle of the model car.
$ roslaunch heading heading_odroid.launch
$ rostopic echo /model_car/yaw
Dahlem Center for Machine Learning & Robotics, Freie Universität Berlin
- Home
- Android App
- Autostart
- Bag file Samples
- Compile ROS Packages
- Compile Arduino from Odroid
- Connect to the Odroid
- Cross compile
- Install ROS indigo
- Multiple Machines
- Navigation
- Network
- Visualize Model car's sensor data
- Web Control Center
- Hardware
- Basic Packages version 1.1
- Flashing the eMMC
- Arduino MAIN v1
- Compile Realsense Camera Library
- Patch for Model Car
- Hardware (AutoNOMOS Model v2)
- Basic Packages (AutoNOMOS Model v2)
- Flashing the eMMC (AutoNOMOS Model v2)
- Getting started (AutoNOMOS Model v2)
- Arduino MAIN (AutoNOMOS Model v2)
- Hardware (AutoNOMOS Model v3)
- Basic Packages (AutoNOMOS Model v3)
- Arduino MAIN v3
- Flashing the eMMC (AutoNOMOS Model v3)
- Patch for Realsense IR/Depth Images (AutoNOMOS Model v3)