The scalaser package was created as a part of the bachelor thesis of Miro Voellmy. It was specifically developed for stair climbing wheelchair Scalevo.
The scalaser package has been tested under ROS Indigo and Ubuntu 14.04. This is research code, expect that it changes often and any fitness for a particular purpose is disclaimed.
The source code is released under a BSD 3-Clause license.
Author: Miro Voellmy
Contact: Miro Voellmy, [email protected]
Affiliation: Autonomous Systems Lab, ETH Zurich
If you use this work in an academic context, please cite the following publication(s):
- M. Voellmy, P. Fankhauser, M. Hutter, and R. Siegwart: Stairrecognition on a stair climbing wheelchair using LIDAR Sensors. IEEE/RSJ International Conference of Placeholders (IROS), 2015. (PDF)
- Robot Operating System (ROS) (middleware for robotics),
- Eigen (linear algebra library),
- Matlab (matlab),
- c_matlabcppinterface (matlab C++ interface),
- scalevo_msgs (messages package of scalevo),
- scalebot (robot model of the scalevo wheelchair)
In order to install, clone the latest version from this repository into your catkin workspace and compile the package using
cd catkin_workspace/src
git clone https://github.com/scalevo/scalaser.git
cd ../
catkin_make
Package tests have not been implemented yet. You can run this command however to watch Starwars Episode IV in the terminal:
telnet towel.blinkenlights.nl
First start the two SICK sensors on board of the Scalevo wheelchair using
roslaunch scalaser pointcloud_2.launch
then start the stair recognition node with
roslaunch scalaser angle.launch
Check the launch files if you want to change a modifiable parameters.
Main node to determine the angle of the stair on stairs.
-
cloud_1
([sensor_msgs/PointCloud])Pointcloud of the right laser sensor.
-
cloud_2
([sensor_msgs/PointCloud])Pointcloud of the left laser sensor.
-
beta
([std_msgs/Float64])Angle of the wheelchair on the stairs.
-
stair_parameters
([std_msgs/Float64MultiArray])Determined parameters of the stair and the wheelchairs position on the stair.
-
stair_model
(visualization_msgs/Marker)The marker for the stair visualization in rviz.
-
chair_model
(visualization_msgs/Marker)The marker for the chair visualization in rviz.
-
trigger
(std_srvs/Empty)Trigger the computation process. For example, you can trigger the computation from the console with
rosservice call /NODE_A_NAME/trigger
-
scalaser/fov_s
(int, default: 200)The start of the field of view.
-
scalaser/fov_s
(int, default: 150)The size of the field of view.
-
scalaser/kp
(double, default: 0.008)P value used to determine the motor velocity.
Publishes a model of the stairs for visualization in rviz.
Publishes a model of the wheelchair positioned on the stairs for visualization in rviz.
Please report bugs and request features using the issue feature of this package.