[Documentation] [TitleIndex] [WordIndex

Only released in EOL distros:  

lama_core: lama_interfaces | lama_jockeys | lama_msgs

Package Summary

The lama_interfaces package provides the interfaces between ROS nodes (such as jockeys from lama_jockeys) and the map.

lama_interfaces provides the interfaces to the database as ROS services for the Large Maps Framework (LaMa).

Overview

lama_interfaces provides the interfaces to the database as ROS services.

The data storage is realized through a database. All databases supported by Python sqlalchemy can be used. The default database is an SQLite database which will be save as ~/.ros/lama.sqlite. The environment is represented as a directed graph, where vertices are points of interest such as crossings. Descriptors can be associated to vertices and edges, they give some information about the environment, so that jockeys can localize or drive the robot. Any ROS message can be saved as descriptor after a trivial implementation of two services (srv files), one to write the descriptor into the database and one to retrieve it. Other variable types can use the blob/Blob message type. Descriptor storage occurs either in binary or clear-text mode.

Usage

The first node that should be used when working with the LaMa Framework is map_node:

rosrun lama_interfaces map_node

This node will run several services: /lama_map_agent, /interface_factory, /lama_object_getter, and /lama_object_setter, which are described in further sections.

LaMa Map Agent

This service of type lama_interfaces/ActOnMap is used for all actions over vertices and edges in the map.

Interface Factory

This service of type lama_interfaces/AddInterface is used to generate two services for each descriptor type, one to write the descriptor into the database and one to retrieve it. Descriptor storage occurs either in binary or clear-text mode (specified through the interface_type service attribute. The name of these two services will be the name of the interface (interface_name attribute) to which "_getter" or "_setter" are added.

For example, to create a clear-text interface for float64 in C++:

   1 ros::NodeHandle nh;
   2 ros::ServiceClient client = nh.serviceClient<lama_interfaces::AddInterface>("interface_factory");
   3 client.waitForExistence();
   4 lama_interfaces::AddInterface srv;
   5 srv.request.interface_name = "my_interface";
   6 srv.request.interface_type = lama_interfaces::AddInterfaceRequest::CLEARTEXT;
   7 srv.request.get_service_message = "lama_interfaces/GetDouble";
   8 srv.request.set_service_message = "lama_interfaces/SetDouble";
   9 if (!client.call(srv))
  10 {
  11   ROS_ERROR("Failed to create the Lama interface %s", srv.request.interface_name.c_str());
  12   return false;
  13 }

To add a database interface in Python, one can either use the /interface_factory service or call the equivalent Python function. For example, for a "sensor_msgs/LaserScan[]" descriptor with binary storage:

   1 from lama_interfaces.interface_factory import interface_factory
   2 interface_name = 'my_laser_descriptor'
   3 getter_service = 'lama_interfaces/GetVectorLaserScan'
   4 setter_service = 'lama_interfaces/SetVectorLaserScan'
   5 
   6 # The node must be running before calling interface_factory
   7 iface = interface_factory(interface_name,
   8                           getter_service,
   9                           setter_service,
  10                           start=True)
  11 
  12 # iface contains the service proxies for getter and setter services,
  13 # if start=True is given.
  14 get_srv = iface.getter_service_proxy
  15 set_srv = iface.setter_service_proxy

Direct vertex/edge access

The services /lama_object_getter and /lama_object_setter provide direct access to the graph vertices or edges. These functionalities are provided by the /lama_map_agent, which should be preferred.


2022-05-28 12:44