Raspberry Pi MouseのROSサンプルコード集です。
ナビゲーションのサンプルはこちら。 ROS 2のサンプルコード集はこちら。
- Raspberry Pi Mouse
- https://rt-net.jp/products/raspberrypimousev3/
- Linux OS
- Ubuntu server 16.04
- Ubuntu server 18.04
- Ubuntu server 20.04
- https://ubuntu.com/download/raspberry-pi
- Device Driver
- ROS
- Raspberry Pi Mouse ROS package
- Remote Computer (Optional)
- ROS
- Raspberry Pi Mouse ROS package
cd ~/catkin_ws/src
# Clone ROS packages
git clone https://github.com/ryuichiueda/raspimouse_ros_2
git clone -b $ROS_DISTRO-devel https://github.com/rt-net/raspimouse_ros_examples
# For direction control example
git clone https://github.com/rt-net/rt_usb_9axisimu_driver
# Install dependencies
rosdep install -r -y --from-paths . --ignore-src
# make & install
cd ~/catkin_ws && catkin_make
source devel/setup.bash
このリポジトリはApache 2.0ライセンスの元、公開されています。 ライセンスについてはLICENSEを参照ください。
teleop_twist_keyboardを使ってRaspberryPiMouseを動かします。
- Keyboard
次のコマンドでノードを起動します。
roslaunch raspimouse_ros_examples teleop.launch key:=true
# Control from remote computer
roslaunch raspimouse_ros_examples teleop.launch key:=true mouse:=false
ノードが起動したら/motor_on
サービスをコールします。
rosservice call /motor_on
ジョイスティックコントローラでRaspberryPiMouseを動かすコード例です。
- Joystick Controller
次のコマンドでノードを起動します。
roslaunch raspimouse_ros_examples teleop.launch joy:=true
# Use DUALSHOCK 3
roslaunch raspimouse_ros_examples teleop.launch joy:=true joyconfig:="dualshock3"
# Control from remote computer
roslaunch raspimouse_ros_examples teleop.launch joy:=true mouse:=false
デフォルトのキー割り当てはこちらです。
./config/joy_f710.yml、./config/joy_dualshock3.yml のキー番号を編集することで、キー割り当てを変更できます。
button_shutdown_1 : 8
button_shutdown_2 : 9
button_motor_off : 8
button_motor_on : 9
button_cmd_enable : 4
色情報をもとにオレンジ色のボールの追跡を行うコード例です。 USB接続のWebカメラとOpenCVを使ってボール追跡をします。
- Webカメラ
- カメラマウント
- ボール(Optional)
- Software
- python
- opencv
- numpy
- v4l-utils
- python
Raspberry Pi Mouseにカメラマウントを取り付け,WebカメラをRaspberry Piに接続します.
次のコマンドで、カメラ制御用のパッケージ(v4l-utils)をインストールします。
sudo apt install v4l-utils
次のスクリプトを実行して、カメラの自動調節機能(自動露光,オートホワイトバランス等)を切ります。
rosrun raspimouse_ros_examples camera.bash
次のコマンドでノードを起動します。
roslaunch raspimouse_ros_examples object_tracking.launch
物体検出画像はbinary
とobject
というトピックとして発行されます。
これらの画像はRViz
やrqt_image_view
で表示できます。
追跡対象の色を変更するには
./scripts/object_tracking.py
を編集します。
def detect_ball(self):
# ~~~ 省略 ~~~
min_hsv, max_hsv = self.set_color_orange()
# min_hsv, max_hsv = self.set_color_green()
# min_hsv, max_hsv = self.set_color_blue()
反応が悪い時にはカメラの露光や関数内のパラメータを調整して下さい.
def set_color_orange(self):
# [H(0~180), S(0~255), V(0~255)]
# min_hsv_orange = np.array([15, 200, 80])
min_hsv_orange = np.array([15, 150, 40])
max_hsv_orange = np.array([20, 255, 255])
return min_hsv_orange, max_hsv_orange
ライントレースのコード例です。
- ライントレースセンサ
- フィールドとライン (Optional)
Raspberry Pi Mouseにライントレースセンサを取り付けます。
次のコマンドでノードを起動します。
roslaunch raspimouse_ros_examples line_follower.launch
# Control from remote computer
roslaunch raspimouse_ros_examples line_follower.launch mouse:=false
Raspberry Pi Mouseをフィールドに置き、SW2を押してフィールド上のセンサ値をサンプリングします。
次に、センサとラインが重なるようにRaspberry Pi Mouseを置き、SW1を押してライン上のセンサ値をサンプリングします。
最後に、ライン上にRaspberry Pi Mouseを置き、SW0を押してライントレースを開始します。
もう一度SW0を押すとライントレースを停止します。
走行速度を変更するには./scripts/line_follower.py
を編集します。
def _publish_cmdvel_for_line_following(self):
VEL_LINER_X = 0.08 # m/s
VEL_ANGULAR_Z = 0.8 # rad/s
LOW_VEL_ANGULAR_Z = 0.5 # rad/s
cmd_vel = Twist()
LiDARを使ってSLAM(自己位置推定と地図作成)を行うサンプルです。
- LiDAR
- LiDAR Mount
- Joystick Controller (Optional)
RPLIDARについては、パッケージrplidar_ros がROS Noetic向けにリリースされていないため動作確認していません。
Raspberry Pi MouseにLiDARを取り付けます。
Raspberry Pi Mouse上で次のコマンドでノードを起動します。
# URG
roslaunch raspimouse_ros_examples mouse_with_lidar.launch urg:=true port:=/dev/ttyACM0
# LDS
roslaunch raspimouse_ros_examples mouse_with_lidar.launch lds:=true port:=/dev/ttyUSB0
Raspberry Pi Mouseを動かすためteleop.launch
を起動します
# joystick control
roslaunch raspimouse_ros_examples teleop.launch mouse:=false joy:=true joyconfig:=dualshock3
次のコマンドでSLAMパッケージを起動します。(Remote computerでの実行推奨)
# URG
roslaunch raspimouse_ros_examples slam_gmapping.launch urg:=true
# LDS
roslaunch raspimouse_ros_examples slam_gmapping.launch lds:=true
Raspberry Pi Mouseを動かして地図を作成します。
次のコマンドで作成した地図を保存します。
mkdir ~/maps
rosrun map_server map_saver -f ~/maps/mymap
./launch/slam_gmapping.launchでgmappingパッケージのパラメータを調整します。
<node pkg="gmapping" type="slam_gmapping" name="raspimouse_slam_gmapping" output="screen">
<!-- <remap from="scan" to="base_scan"/> -->
<param name="base_frame" value="base_link" />
<param name="odom_frame" value="odom" />
<param name="map_frame" value="map" />
<param name="map_update_interval" value="1.0"/>
<param name="maxUrange" value="5.6" if="$(arg urg)"/>
<param name="maxUrange" value="12" if="$(arg rplidar)"/>
<param name="maxUrange" value="3.5" if="$(arg lds)"/>
<!-- <param name="sigma" value="0.05"/> -->
<!-- <param name="kernelSize" value="1"/> -->
<!-- <param name="lstep" value="0.05"/> -->
IMUセンサを使用した角度制御のコード例です。
- USB出力9軸IMUセンサモジュール
- LiDAR Mount
- RT-USB-9axisIMU ROS Package.
LiDAR MountにIMUセンサモジュールを取り付けます。
Raspberry Pi Mouse にLiDAR Mountを取り付けます。
次のコマンドでノードを起動します。
roslaunch raspimouse_ros_examples direction_control.launch
SW0 ~ SW2を押して動作モードを切り替えます。
- SW0: ジャイロセンサのバイアスをキャリブレーションし、ラズパイマウスの方位角を
0 rad
にリセットします - SW1: 方位角を
0 rad
に維持する角度制御を開始します- SW0 ~ SW2を押すか、ラズパイマウス本体を横に傾けると終了します
- SW2: 方位角を
-π ~ π rad
に変化させる角度制御を開始します- SW0 ~ SW2を押すか、ラズパイマウス本体を横に傾けると終了します
角度制御に使うPID制御器のゲインを変更するには./scripts/direction_control.py
を編集します。
class DirectionController(object):
# ---
def __init__(self):
# ---
# for angle control
self._omega_pid_controller = PIDController(10, 0, 20)