[PYTHON] ROS Lecture 108 Using Database (mongo) with ROS

environment

This article works in the following environment.

item value
CPU Core i5-8250U
Ubuntu 16.04
ROS Kinetic
python 2.7.12
mongodb 2.6.10

For installation, refer to ROS Course 02 Installation. Also, the program in this article has been uploaded to github. See ROS Course 11 git repository.

Overview

In ROS, information is basically stored in rosbag, but this is a debug log-like thing that humans look back at later, and database-like data to be reused at runtime is saved by each node or a file is written by itself. There is no choice but to read. What comes out here is DataBase, and ROS publishes a package called mongodb that connects to DataBase.

mongodb configuration

mongodb has a structure of database-> collection-> document.

Installation

mongodb_store installation


sudo apt install ros-kinetic-mongodb-store

Try writing with mongodb_store

Run DataBase

Decide the directory where you want to put the database files at startup. Create an empty directory. If you specify a directory that does not exist, an error will occur.

mongodb_Run store


mkdir /tmp/test_db
roslaunch mongodb_store mongodb_store.launch db_path:=/tmp/test_db port:=27017

Write node execution

web_lecture/scripts/mongo_pose_write.py


#!/usr/bin/env python
# -*- coding: utf-8 -*-

import rospy
from mongodb_store.message_store import MessageStoreProxy
from geometry_msgs.msg import Pose, Point, Quaternion

if __name__ == '__main__':
    rospy.init_node("mongo_pose_write")

    msg_store = MessageStoreProxy(database="srs", collection="pose1")
    p = Pose(Point(0, 1, 2), Quaternion(0, 0, 0, 1))

    try:
        p_id = msg_store.insert_named("named_pose", p)
        p_id = msg_store.insert(p)

    except rospy.ServiceException, e:
        print "Service call failed: %s"%e

Write node execution


rosrun web_lecture mongo_pose_write.py

Run read node

web_lecture/scripts/mongo_pose_read.py


#!/usr/bin/env python
# -*- coding: utf-8 -*-

import rospy
import mongodb_store_msgs.srv as dc_srv
import mongodb_store.util as dc_util
from mongodb_store.message_store import MessageStoreProxy
from geometry_msgs.msg import Pose, Point, Quaternion
import StringIO

if __name__ == '__main__':
    rospy.init_node("mongo_pose_write")

    msg_store = MessageStoreProxy(database="srs", collection="pose1")

    try:
        for item in msg_store.query(Pose._type):
            print item[0].position

    except rospy.ServiceException, e:
        print "Service call failed: %s"%e

Run read node


rosrun web_lecture mongo_pose_read.py 

Execution result


x: 0.0
y: 1.0
z: 2.0
x: 0.0
y: 1.0
z: 2.0

Read data with mongo

You can also read the database directly instead of the ROS interface.

Invoking the command mongo will connect you to the mongo console.

comment

If mongodb is already running behind the scenes, port27017 is suppressed, so roslaunch will result in an error. Let's see if service is started with systemctl status mongodb.service. If it is up, stop it with sudo systemctl disable mongodb.service && sudo systemctl stop mongodb.service.

reference

mongodb_store

Link to table of contents page

Link to ROS course table of contents

Recommended Posts

ROS Lecture 108 Using Database (mongo) with ROS
ROS Lecture 113 Perform tasks with smach
I tried using a database (sqlite3) with kivy
Fix database with pytest-docker
Database search with db.py
Secure ROS with AppArmor
Touch NoSQL with Python using the Oracle NoSQL Database Cloud Simulator
Using X11 with ubuntu18.04 (C)
When using optparse with iPython
Using Graphviz with Jupyter Notebook
[S3] CRUD with S3 using Python [Python]
Messaging with AMQP using kombu
Using Quaternion with Python ~ numpy-quaternion ~
Try using matplotlib with PyCharm
Games using IMU with SenseHat
[Python] Using OpenCV with Python (Basic)
Using a printer with Debian 10
ROS course 105 Operate toio with ROS
Try using folium with anaconda
Using OpenCV with Python @Mac
Send using Python with Gmail
ROS Lecture 114 DataBase handles images and accesses them from a browser