-
Notifications
You must be signed in to change notification settings - Fork 24
Basic packages Version 3
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 1: Basic ROS Packages preinstalled in the car.
To update to the newest version of the packages, download the debian package from: modelcar-basic-packages.deb
Copy the file to the model car and install it with:
$ dpkg -i modelcar-basic-packages.deb
Make sure in the .bashrc you are sourcing the correct setup.bash file (any catkin workspace in the /root/ directory has to source it before the first build):
source /opt/ros/modelcar/catkin_ws/install/setup.bash
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/ttyLidar) 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/ttyLidar"/>
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_speed Node sends desired steering angle and light and speed commands 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)
manual_control/speed (std_msgs/Int16)
manual_control/stop_start (std_msgs/Int16)
serial_port (string,default: /dev/ttyArduino) 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_speed servo_light_odroid.launch
$ rostopic pub -r 1 /manual_control/steering std_msgs/Int16 '{data: 90}'
$ rostopic pub -r 1 /manual_control/speed std_msgs/Int16 '{data: 500}'
$ rostopic pub -r 1 /manual_control/lights std_msgs/String '{data: le}'
resolution of servo motor=?! resolution of speed motor=?
This node used to read the yaw angle, delta_time between ticks of encoder, encoder counters through the serial port from Arduino and publish yaw angle, motor speed (rad/s) and motor revolutions.
model_car/yaw (std_msgs/Float32)
model_car/revolutions (std_msgs/Float32)
model_car/twist (geometry_msgs/Twist)
serial_port (string,default: /dev/ttyArduino)
serial_baudrate (int, default: 115200)
Start a head_twist_revolutions node and subscribe to the yaw angle,twist,revolutions of the model car.
$ roslaunch head_twist_revolutions head_twist_revolutions_odroid.launch
$ rostopic echo /model_car/yaw
$ rostopic echo /model_car/twist
$ rostopic echo /model_car/revolutions
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/usb_cam" />
This package contains launch files for using the Intel RealSense camera device.
Start realsense_sr300 node to start the intel sr300 camera.
$ roslaunch realsense_camera sr300_nodelet_rgbd_app.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
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)